Commit 3987ea37 authored by Gregory Dymarek's avatar Gregory Dymarek

Android Joystick support

parent 6af64398
......@@ -266,6 +266,7 @@ HEADERS += \
src/HomePositionManager.h \
src/Joystick/Joystick.h \
src/Joystick/JoystickManager.h \
src/VehicleSetup/JoystickConfigController.h \
src/FollowMe/FollowMe.h \
src/PositionManager/SimulatedPosition.h \
src/JsonHelper.h \
......@@ -314,6 +315,11 @@ HEADERS += \
src/QtLocationPlugin/QMLControl/QGCMapEngineManager.h \
src/PositionManager/PositionManager.h
AndroidBuild {
HEADERS += \
src/Joystick/JoystickAndroid.h \
}
DebugBuild {
HEADERS += \
src/comm/MockLink.h \
......@@ -346,6 +352,7 @@ HEADERS += \
src/comm/QGCHilLink.h \
src/comm/QGCJSBSimLink.h \
src/comm/QGCXPlaneLink.h \
src/Joystick/JoystickSDL.h \
src/QGCFileDialog.h \
src/QGCMessageBox.h \
src/uas/FileManager.h \
......@@ -390,7 +397,6 @@ HEADERS += \
src/GPS/GPSManager.h \
src/GPS/GPSPositionMessage.h \
src/GPS/GPSProvider.h \
src/VehicleSetup/JoystickConfigController.h \
src/ViewWidgets/CustomCommandWidget.h \
src/ViewWidgets/CustomCommandWidgetController.h \
src/ViewWidgets/LogDownload.h \
......@@ -403,8 +409,10 @@ iOSBuild {
src/audio/QGCAudioWorker_iOS.mm \
src/MobileScreenMgr.mm \
}
AndroidBuild {
SOURCES += src/MobileScreenMgr.cc \
src/Joystick/JoystickAndroid.cc \
}
......@@ -423,6 +431,7 @@ SOURCES += \
src/HomePositionManager.cc \
src/Joystick/Joystick.cc \
src/Joystick/JoystickManager.cc \
src/VehicleSetup/JoystickConfigController.cc \
src/JsonHelper.cc \
src/FollowMe/FollowMe.cc \
src/LogCompressor.cc \
......@@ -501,6 +510,7 @@ SOURCES += \
src/comm/QGCFlightGearLink.cc \
src/comm/QGCJSBSimLink.cc \
src/comm/QGCXPlaneLink.cc \
src/Joystick/JoystickSDL.cc \
src/ui/HILDockWidget.cc \
src/ui/linechart/ChartPlot.cc \
src/ui/linechart/IncrementalPlot.cc \
......@@ -531,7 +541,6 @@ SOURCES += \
src/GPS/RTCM/RTCMMavlink.cc \
src/GPS/GPSManager.cc \
src/GPS/GPSProvider.cc \
src/VehicleSetup/JoystickConfigController.cc \
src/ViewWidgets/CustomCommandWidget.cc \
src/ViewWidgets/CustomCommandWidgetController.cc \
src/ViewWidgets/LogDownload.cc \
......
......@@ -28,14 +28,6 @@
#include <QSettings>
#ifndef __mobile__
#ifdef Q_OS_MAC
#include <SDL.h>
#else
#include <SDL/SDL.h>
#endif
#endif
QGC_LOGGING_CATEGORY(JoystickLog, "JoystickLog")
QGC_LOGGING_CATEGORY(JoystickValuesLog, "JoystickValuesLog")
......@@ -51,9 +43,7 @@ const char* Joystick::_rgFunctionSettingsKey[Joystick::maxFunction] = {
"ThrottleAxis"
};
Joystick::Joystick(const QString& name, int axisCount, int buttonCount, int sdlIndex, MultiVehicleManager* multiVehicleManager)
#ifndef __mobile__
: _sdlIndex(sdlIndex)
Joystick::Joystick(const QString& name, int axisCount, int buttonCount, MultiVehicleManager* multiVehicleManager)
, _exitThread(false)
, _name(name)
, _axisCount(axisCount)
......@@ -68,15 +58,7 @@ Joystick::Joystick(const QString& name, int axisCount, int buttonCount, int sdlI
, _activeVehicle(NULL)
, _pollingStartedForCalibration(false)
, _multiVehicleManager(multiVehicleManager)
#endif // __mobile__
{
#ifdef __mobile__
Q_UNUSED(name)
Q_UNUSED(axisCount)
Q_UNUSED(buttonCount)
Q_UNUSED(sdlIndex)
Q_UNUSED(multiVehicleManager)
#else
_rgAxisValues = new int[_axisCount];
_rgCalibration = new Calibration_t[_axisCount];
_rgButtonValues = new bool[_buttonCount];
......@@ -90,21 +72,16 @@ Joystick::Joystick(const QString& name, int axisCount, int buttonCount, int sdlI
}
_loadSettings();
#endif // __mobile__
}
Joystick::~Joystick()
{
#ifndef __mobile__
delete _rgAxisValues;
delete _rgCalibration;
delete _rgButtonValues;
delete _rgButtonActions;
#endif
}
#ifndef __mobile__
void Joystick::_loadSettings(void)
{
QSettings settings;
......@@ -257,19 +234,14 @@ float Joystick::_adjustRange(int value, Calibration_t calibration)
void Joystick::run(void)
{
SDL_Joystick* sdlJoystick = SDL_JoystickOpen(_sdlIndex);
if (!sdlJoystick) {
qCWarning(JoystickLog) << "SDL_JoystickOpen failed:" << SDL_GetError();
return;
}
open();
while (!_exitThread) {
SDL_JoystickUpdate();
update();
// Update axes
for (int axisIndex=0; axisIndex<_axisCount; axisIndex++) {
int newAxisValue = SDL_JoystickGetAxis(sdlJoystick, axisIndex);
int newAxisValue = getAxis(axisIndex);
// Calibration code requires signal to be emitted even if value hasn't changed
_rgAxisValues[axisIndex] = newAxisValue;
emit rawAxisValueChanged(axisIndex, newAxisValue);
......@@ -277,7 +249,7 @@ void Joystick::run(void)
// Update buttons
for (int buttonIndex=0; buttonIndex<_buttonCount; buttonIndex++) {
bool newButtonValue = !!SDL_JoystickGetButton(sdlJoystick, buttonIndex);
bool newButtonValue = getButton(buttonIndex);
if (newButtonValue != _rgButtonValues[buttonIndex]) {
_rgButtonValues[buttonIndex] = newButtonValue;
emit rawButtonPressedChanged(buttonIndex, newButtonValue);
......@@ -362,7 +334,7 @@ void Joystick::run(void)
QGC::SLEEP::msleep(40);
}
SDL_JoystickClose(sdlJoystick);
close();
}
void Joystick::startPolling(Vehicle* vehicle)
......@@ -579,4 +551,3 @@ bool Joystick::_validButton(int button)
return button >= 0 && button < _buttonCount;
}
#endif // __mobile__
......@@ -39,9 +39,9 @@ class Joystick : public QThread
Q_OBJECT
public:
Joystick(const QString& name, int axisCount, int buttonCount, int sdlIndex, MultiVehicleManager* multiVehicleManager);
Joystick(const QString& name, int axisCount, int buttonCount, MultiVehicleManager* multiVehicleManager);
~Joystick();
typedef struct {
int min;
int max;
......@@ -63,7 +63,6 @@ public:
ThrottleModeMax
} ThrottleMode_t;
#ifndef __mobile__
Q_PROPERTY(QString name READ name CONSTANT)
Q_PROPERTY(bool calibrated MEMBER _calibrated NOTIFY calibratedChanged)
......@@ -137,7 +136,7 @@ signals:
void buttonActionTriggered(int action);
private:
protected:
void _saveSettings(void);
void _loadSettings(void);
float _adjustRange(int value, Calibration_t calibration);
......@@ -145,11 +144,18 @@ private:
bool _validAxis(int axis);
bool _validButton(int button);
private:
virtual bool open() = 0;
virtual void close() = 0;
virtual bool update() = 0;
virtual bool getButton(int i) = 0;
virtual int getAxis(int i) = 0;
// Override from QThread
virtual void run(void);
private:
int _sdlIndex; ///< Index for SDL_JoystickOpen
protected:
bool _exitThread; ///< true: signal thread to exit
......@@ -174,7 +180,6 @@ private:
bool _pollingStartedForCalibration;
MultiVehicleManager* _multiVehicleManager;
#endif // __mobile__
private:
static const char* _rgFunctionSettingsKey[maxFunction];
......
#include "JoystickAndroid.h"
#include "QGCApplication.h"
#include <QQmlEngine>
int JoystickAndroid::_androidBtnListCount;
int *JoystickAndroid::_androidBtnList;
int JoystickAndroid::ACTION_DOWN;
int JoystickAndroid::ACTION_UP;
QMutex JoystickAndroid::m_mutex;
JoystickAndroid::JoystickAndroid(const QString& name, int axisCount, int buttonCount, int id, MultiVehicleManager* multiVehicleManager)
: Joystick(name,axisCount,buttonCount,multiVehicleManager)
, deviceId(id)
{
int i;
QAndroidJniEnvironment env;
QAndroidJniObject inputDevice = QAndroidJniObject::callStaticObjectMethod("android/view/InputDevice", "getDevice", "(I)Landroid/view/InputDevice;", id);
//set button mapping (number->code)
jintArray b = env->NewIntArray(_androidBtnListCount);
env->SetIntArrayRegion(b,0,_androidBtnListCount,_androidBtnList);
QAndroidJniObject btns = inputDevice.callObjectMethod("hasKeys", "([I)[Z", b);
jbooleanArray jSupportedButtons = btns.object<jbooleanArray>();
jboolean* supportedButtons = env->GetBooleanArrayElements(jSupportedButtons, nullptr);
//create a mapping table (btnCode) that maps button number with button code
btnValue = new bool[_buttonCount];
btnCode = new int[_buttonCount];
int c = 0;
for (i=0;i<_androidBtnListCount;i++)
if (supportedButtons[i]) {
btnValue[c] = false;
btnCode[c] = _androidBtnList[i];
c++;
}
env->ReleaseBooleanArrayElements(jSupportedButtons, supportedButtons, 0);
//set axis mapping (number->code)
axisValue = new int[_axisCount];
axisCode = new int[_axisCount];
QAndroidJniObject rangeListNative = inputDevice.callObjectMethod("getMotionRanges", "()Ljava/util/List;");
for (i=0;i<_axisCount;i++) {
QAndroidJniObject range = rangeListNative.callObjectMethod("get", "(I)Ljava/lang/Object;",i);
axisCode[i] = range.callMethod<jint>("getAxis");
axisValue[i] = 0;
}
qCDebug(JoystickLog) << "axis:" <<_axisCount << "buttons:" <<_buttonCount;
QtAndroidPrivate::registerGenericMotionEventListener(this);
QtAndroidPrivate::registerKeyEventListener(this);
}
JoystickAndroid::~JoystickAndroid() {
delete btnCode;
delete axisCode;
delete btnValue;
delete axisValue;
QtAndroidPrivate::unregisterGenericMotionEventListener(this);
QtAndroidPrivate::unregisterKeyEventListener(this);
}
QMap<QString, Joystick*> JoystickAndroid::discover(MultiVehicleManager* _multiVehicleManager) {
bool joystickFound = false;
static QMap<QString, Joystick*> ret;
_initStatic(); //it's enough to run it once, should be in a static constructor
QMutexLocker lock(&m_mutex);
QAndroidJniEnvironment env;
QAndroidJniObject o = QAndroidJniObject::callStaticObjectMethod<jintArray>("android/view/InputDevice", "getDeviceIds");
jintArray jarr = o.object<jintArray>();
int sz = env->GetArrayLength(jarr);
jint *buff = env->GetIntArrayElements(jarr, nullptr);
int SOURCE_GAMEPAD = QAndroidJniObject::getStaticField<jint>("android/view/InputDevice", "SOURCE_GAMEPAD");
int SOURCE_JOYSTICK = QAndroidJniObject::getStaticField<jint>("android/view/InputDevice", "SOURCE_JOYSTICK");
for (int i = 0; i < sz; ++i) {
QAndroidJniObject inputDevice = QAndroidJniObject::callStaticObjectMethod("android/view/InputDevice", "getDevice", "(I)Landroid/view/InputDevice;", buff[i]);
int sources = inputDevice.callMethod<jint>("getSources", "()I");
if (((sources & SOURCE_GAMEPAD) != SOURCE_GAMEPAD) //check if the input device is interesting to us
&& ((sources & SOURCE_JOYSTICK) != SOURCE_JOYSTICK)) continue;
//get id and name
QString id = inputDevice.callObjectMethod("getDescriptor", "()Ljava/lang/String;").toString();
QString name = inputDevice.callObjectMethod("getName", "()Ljava/lang/String;").toString();
if (joystickFound) { //skipping {
qWarning() << "Skipping joystick:" << name;
continue;
}
//get number of axis
QAndroidJniObject rangeListNative = inputDevice.callObjectMethod("getMotionRanges", "()Ljava/util/List;");
int axisCount = rangeListNative.callMethod<jint>("size");
//get number of buttons
jintArray a = env->NewIntArray(_androidBtnListCount);
env->SetIntArrayRegion(a,0,_androidBtnListCount,_androidBtnList);
QAndroidJniObject btns = inputDevice.callObjectMethod("hasKeys", "([I)[Z", a);
jbooleanArray jSupportedButtons = btns.object<jbooleanArray>();
jboolean* supportedButtons = env->GetBooleanArrayElements(jSupportedButtons, nullptr);
int buttonCount = 0;
for (int j=0;j<_androidBtnListCount;j++)
if (supportedButtons[j]) buttonCount++;
env->ReleaseBooleanArrayElements(jSupportedButtons, supportedButtons, 0);
qCDebug(JoystickLog) << "\t" << name << "id:" << buff[i] << "axes:" << axisCount << "buttons:" << buttonCount;
ret[name] = new JoystickAndroid(name, axisCount, buttonCount, buff[i], _multiVehicleManager);
joystickFound = true;
}
env->ReleaseIntArrayElements(jarr, buff, 0);
return ret;
}
bool JoystickAndroid::handleKeyEvent(jobject event) {
QJNIObjectPrivate ev(event);
QMutexLocker lock(&m_mutex);
const int _deviceId = ev.callMethod<jint>("getDeviceId", "()I");
if (_deviceId!=deviceId) return false;
const int action = ev.callMethod<jint>("getAction", "()I");
const int keyCode = ev.callMethod<jint>("getKeyCode", "()I");
for (int i=0;i<_buttonCount;i++) {
if (btnCode[i]==keyCode) {
if (action==ACTION_DOWN) btnValue[i] = true;
if (action==ACTION_UP) btnValue[i] = false;
return true;
}
}
return false;
}
bool JoystickAndroid::handleGenericMotionEvent(jobject event) {
QJNIObjectPrivate ev(event);
QMutexLocker lock(&m_mutex);
const int _deviceId = ev.callMethod<jint>("getDeviceId", "()I");
if (_deviceId!=deviceId) return false;
for (int i=0;i<_axisCount;i++) {
const float v = ev.callMethod<jfloat>("getAxisValue", "(I)F",axisCode[i]);
axisValue[i] = (int)(v*32767.f);
}
return true;
}
bool JoystickAndroid::open(void) {
return true;
}
void JoystickAndroid::close(void) {
}
bool JoystickAndroid::update(void)
{
return true;
}
bool JoystickAndroid::getButton(int i) {
return btnValue[ i ];
}
int JoystickAndroid::getAxis(int i) {
return axisValue[ i ];
}
//helper method
void JoystickAndroid::_initStatic() {
//this gets list of all possible buttons - this is needed to check how many buttons our gamepad supports
//instead of the whole logic below we could have just a simple array of hardcoded int values as these 'should' not change
//int JoystickAndroid::_androidBtnListCount;
_androidBtnListCount = 31;
static int ret[31]; //there are 31 buttons in total accordingy to the API
int i;
//int *JoystickAndroid::
_androidBtnList = ret;
for (i=1;i<=16;i++) {
QString name = "KEYCODE_BUTTON_"+QString::number(i);
ret[i-1] = QAndroidJniObject::getStaticField<jint>("android/view/KeyEvent", name.toStdString().c_str());
}
i--;
ret[i++] = QAndroidJniObject::getStaticField<jint>("android/view/KeyEvent", "KEYCODE_BUTTON_A");
ret[i++] = QAndroidJniObject::getStaticField<jint>("android/view/KeyEvent", "KEYCODE_BUTTON_B");
ret[i++] = QAndroidJniObject::getStaticField<jint>("android/view/KeyEvent", "KEYCODE_BUTTON_C");
ret[i++] = QAndroidJniObject::getStaticField<jint>("android/view/KeyEvent", "KEYCODE_BUTTON_L1");
ret[i++] = QAndroidJniObject::getStaticField<jint>("android/view/KeyEvent", "KEYCODE_BUTTON_L2");
ret[i++] = QAndroidJniObject::getStaticField<jint>("android/view/KeyEvent", "KEYCODE_BUTTON_R1");
ret[i++] = QAndroidJniObject::getStaticField<jint>("android/view/KeyEvent", "KEYCODE_BUTTON_R2");
ret[i++] = QAndroidJniObject::getStaticField<jint>("android/view/KeyEvent", "KEYCODE_BUTTON_MODE");
ret[i++] = QAndroidJniObject::getStaticField<jint>("android/view/KeyEvent", "KEYCODE_BUTTON_SELECT");
ret[i++] = QAndroidJniObject::getStaticField<jint>("android/view/KeyEvent", "KEYCODE_BUTTON_START");
ret[i++] = QAndroidJniObject::getStaticField<jint>("android/view/KeyEvent", "KEYCODE_BUTTON_THUMBL");
ret[i++] = QAndroidJniObject::getStaticField<jint>("android/view/KeyEvent", "KEYCODE_BUTTON_THUMBR");
ret[i++] = QAndroidJniObject::getStaticField<jint>("android/view/KeyEvent", "KEYCODE_BUTTON_X");
ret[i++] = QAndroidJniObject::getStaticField<jint>("android/view/KeyEvent", "KEYCODE_BUTTON_Y");
ret[i++] = QAndroidJniObject::getStaticField<jint>("android/view/KeyEvent", "KEYCODE_BUTTON_Z");
ACTION_DOWN = QAndroidJniObject::getStaticField<jint>("android/view/KeyEvent", "ACTION_DOWN");
ACTION_UP = QAndroidJniObject::getStaticField<jint>("android/view/KeyEvent", "ACTION_UP");
}
#ifndef JOYSTICKANDROID_H
#define JOYSTICKANDROID_H
#include "Joystick.h"
#include "Vehicle.h"
#include "MultiVehicleManager.h"
#include <jni.h>
#include <QtCore/private/qjni_p.h>
#include <QtCore/private/qjnihelpers_p.h>
#include <QtAndroidExtras/QtAndroidExtras>
#include <QtAndroidExtras/QAndroidJniObject>
class JoystickAndroid : public Joystick, public QtAndroidPrivate::GenericMotionEventListener, public QtAndroidPrivate::KeyEventListener
{
public:
JoystickAndroid(const QString& name, int axisCount, int buttonCount, int id, MultiVehicleManager* multiVehicleManager);
~JoystickAndroid();
static QMap<QString, Joystick*> discover(MultiVehicleManager* _multiVehicleManager);
private:
bool handleKeyEvent(jobject event);
bool handleGenericMotionEvent(jobject event);
virtual bool open();
virtual void close();
virtual bool update();
virtual bool getButton(int i);
virtual int getAxis(int i);
int *btnCode;
int *axisCode;
bool *btnValue;
int *axisValue;
static void _initStatic();
static int * _androidBtnList; //list of all possible android buttons
static int _androidBtnListCount;
static int ACTION_DOWN, ACTION_UP;
static QMutex m_mutex;
int deviceId;
};
#endif // JOYSTICKANDROID_H
......@@ -27,11 +27,12 @@
#include <QQmlEngine>
#ifndef __mobile__
#ifdef Q_OS_MAC
#include <SDL.h>
#else
#include <SDL/SDL.h>
#endif
#include "JoystickSDL.h"
#define __sdljoystick__
#endif
#ifdef __android__
#include "JoystickAndroid.h"
#endif
QGC_LOGGING_CATEGORY(JoystickManagerLog, "JoystickManagerLog")
......@@ -44,7 +45,15 @@ JoystickManager::JoystickManager(QGCApplication* app)
, _activeJoystick(NULL)
, _multiVehicleManager(NULL)
{
}
JoystickManager::~JoystickManager() {
QMap<QString, Joystick*>::iterator i;
for (i = _name2JoystickMap.begin(); i != _name2JoystickMap.end(); ++i) {
qDebug() << "Releasing joystick:" << i.key();
delete i.value();
}
qDebug() << "Done";
}
void JoystickManager::setToolbox(QGCToolbox *toolbox)
......@@ -55,33 +64,10 @@ void JoystickManager::setToolbox(QGCToolbox *toolbox)
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;
}
// Load available joysticks
qCDebug(JoystickManagerLog) << "Available joysticks";
for (int i=0; i<SDL_NumJoysticks(); i++) {
QString name = SDL_JoystickName(i);
if (!_name2JoystickMap.contains(name)) {
int axisCount, buttonCount;
SDL_Joystick* sdlJoystick = SDL_JoystickOpen(i);
axisCount = SDL_JoystickNumAxes(sdlJoystick);
buttonCount = SDL_JoystickNumButtons(sdlJoystick);
SDL_JoystickClose(sdlJoystick);
qCDebug(JoystickManagerLog) << "\t" << name << "axes:" << axisCount << "buttons:" << buttonCount;
_name2JoystickMap[name] = new Joystick(name, axisCount, buttonCount, i, _multiVehicleManager);
} else {
qCDebug(JoystickManagerLog) << "\tSkipping duplicate" << name;
}
}
#ifdef __sdljoystick__
_name2JoystickMap = JoystickSDL::discover(_multiVehicleManager);
#elif defined(__android__)
_name2JoystickMap = JoystickAndroid::discover(_multiVehicleManager);
#endif
if (!_name2JoystickMap.count()) {
......@@ -92,10 +78,8 @@ void JoystickManager::setToolbox(QGCToolbox *toolbox)
_setActiveJoystickFromSettings();
}
void JoystickManager::_setActiveJoystickFromSettings(void)
{
#ifndef __mobile__
QSettings settings;
settings.beginGroup(_settingsGroup);
......@@ -107,7 +91,6 @@ void JoystickManager::_setActiveJoystickFromSettings(void)
setActiveJoystick(_name2JoystickMap.value(name, _name2JoystickMap.first()));
settings.setValue(_settingsKeyActiveJoystick, _activeJoystick->name());
#endif
}
Joystick* JoystickManager::activeJoystick(void)
......@@ -117,9 +100,6 @@ Joystick* JoystickManager::activeJoystick(void)
void JoystickManager::setActiveJoystick(Joystick* joystick)
{
#ifdef __mobile__
Q_UNUSED(joystick)
#else
QSettings settings;
if (!_name2JoystickMap.contains(joystick->name())) {
......@@ -138,7 +118,6 @@ void JoystickManager::setActiveJoystick(Joystick* joystick)
emit activeJoystickChanged(_activeJoystick);
emit activeJoystickNameChanged(_activeJoystick->name());
#endif
}
QVariantList JoystickManager::joysticks(void)
......@@ -159,11 +138,7 @@ 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)
......
......@@ -41,6 +41,7 @@ class JoystickManager : public QGCTool
public:
JoystickManager(QGCApplication* app);
~JoystickManager();
/// List of available joysticks
Q_PROPERTY(QVariantList joysticks READ joysticks CONSTANT)
......
#include "JoystickSDL.h"
#include "QGCApplication.h"
#include <QQmlEngine>
JoystickSDL::JoystickSDL(const QString& name, int axisCount, int buttonCount, int index, MultiVehicleManager* multiVehicleManager)
: Joystick(name,axisCount,buttonCount,multiVehicleManager)
, _index(index)
{
}
QMap<QString, Joystick*> JoystickSDL::discover(MultiVehicleManager* _multiVehicleManager) {
static QMap<QString, Joystick*> ret;
if (SDL_InitSubSystem(SDL_INIT_JOYSTICK | SDL_INIT_NOPARACHUTE) < 0) {
qWarning() << "Couldn't initialize SimpleDirectMediaLayer:" << SDL_GetError();
return ret;
}
// Load available joysticks
qCDebug(JoystickLog) << "Available joysticks";
for (int i=0; i<SDL_NumJoysticks(); i++) {
QString name = SDL_JoystickName(i);
if (!ret.contains(name)) {
int axisCount, buttonCount;
SDL_Joystick* sdlJoystick = SDL_JoystickOpen(i);
axisCount = SDL_JoystickNumAxes(sdlJoystick);
buttonCount = SDL_JoystickNumButtons(sdlJoystick);
SDL_JoystickClose(sdlJoystick);
qCDebug(JoystickLog) << "\t" << name << "axes:" << axisCount << "buttons:" << buttonCount;
ret[name] = new JoystickSDL(name, axisCount, buttonCount, i, _multiVehicleManager);
} else {
qCDebug(JoystickLog) << "\tSkipping duplicate" << name;
}
}
return ret;
}
bool JoystickSDL::open(void) {
sdlJoystick = SDL_JoystickOpen(_index);
if (!sdlJoystick) {
qCWarning(JoystickLog) << "SDL_JoystickOpen failed:" << SDL_GetError();
return false;
}
return true;
}
void JoystickSDL::close(void) {
SDL_JoystickClose(sdlJoystick);
}
bool JoystickSDL::update(void)
{
SDL_JoystickUpdate();
return true;
}
bool JoystickSDL::getButton(int i) {
return !!SDL_JoystickGetButton(sdlJoystick, i);
}
int JoystickSDL::getAxis(int i) {
return SDL_JoystickGetAxis(sdlJoystick, i);
}
......@@ -85,6 +85,7 @@
#include "PX4/PX4FirmwarePlugin.h"
#include "Vehicle.h"
#include "MavlinkQmlSingleton.h"
#include "JoystickConfigController.h"
#include "JoystickManager.h"
#include "QmlObjectListModel.h"
#include "MissionManager.h"
......@@ -115,7 +116,6 @@
#include "QGCFileDialog.h"
#include "QGCMessageBox.h"
#include "FirmwareUpgradeController.h"
#include "JoystickConfigController.h"
#include "MainWindow.h"
#endif
......@@ -399,12 +399,11 @@ void QGCApplication::_initCommon(void)
qmlRegisterType<ValuesWidgetController> ("QGroundControl.Controllers", 1, 0, "ValuesWidgetController");
qmlRegisterType<QGCMobileFileDialogController> ("QGroundControl.Controllers", 1, 0, "QGCMobileFileDialogController");
qmlRegisterType<RCChannelMonitorController> ("QGroundControl.Controllers", 1, 0, "RCChannelMonitorController");
qmlRegisterType<JoystickConfigController> ("QGroundControl.Controllers", 1, 0, "JoystickConfigController");
#ifndef __mobile__
qmlRegisterType<ViewWidgetController> ("QGroundControl.Controllers", 1, 0, "ViewWidgetController");
qmlRegisterType<CustomCommandWidgetController> ("QGroundControl.Controllers", 1, 0, "CustomCommandWidgetController");
qmlRegisterType<FirmwareUpgradeController> ("QGroundControl.Controllers", 1, 0, "FirmwareUpgradeController");
qmlRegisterType<JoystickConfigController> ("QGroundControl.Controllers", 1, 0, "JoystickConfigController");
qmlRegisterType<LogDownloadController> ("QGroundControl.Controllers", 1, 0, "LogDownloadController");
#endif
......
......@@ -1124,7 +1124,6 @@ void Vehicle::setJoystickEnabled(bool enabled)
void Vehicle::_startJoystick(bool start)
{
#ifndef __mobile__
Joystick* joystick = _joystickManager->activeJoystick();
if (joystick) {
if (start) {
......@@ -1135,9 +1134,6 @@ void Vehicle::_startJoystick(bool start)
joystick->stopPolling();
}
}
#else
Q_UNUSED(start);
#endif
}
bool Vehicle::active(void)
......
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