17#include <QtCore/QApplicationStatic>
18#include <QtCore/QSettings>
19#include <QtGui/QVector3D>
27 , _joystickManagerSettings(
SettingsManager::instance()->joystickManagerSettings())
29 qCDebug(JoystickManagerLog) <<
this;
32 _pollTimer.setInterval(500);
33 (void) connect(&_pollTimer, &QTimer::timeout,
this, []() {
37 (void) connect(_joystickManagerSettings->activeJoystickName(), &
Fact::rawValueChanged,
this, [
this](
const QVariant &value) {
38 QString joystickName = value.toString();
39 _setActiveJoystickByName(joystickName);
42 (void) connect(_joystickManagerSettings->joystickEnabledVehiclesIds(), &
Fact::rawValueChanged,
this, [
this](
const QVariant &value) {
44 auto multiVehicleManager = MultiVehicleManager::instance();
45 auto activeVehicle = multiVehicleManager->activeVehicle();
46 if (activeVehicle && _activeJoystick) {
47 if (_joystickEnabledForVehicle(activeVehicle)) {
48 _activeJoystick->_startPollingForActiveVehicle();
50 _activeJoystick->_stopAllPolling();
53 emit activeJoystickEnabledForActiveVehicleChanged();
64JoystickManager::~JoystickManager()
68 for (QMap<QString, Joystick*>::key_value_iterator it = _name2JoystickMap.keyValueBegin(); it != _name2JoystickMap.keyValueEnd(); ++it) {
69 qCDebug(JoystickManagerLog) <<
"Releasing joystick:" << it->first;
78 qCDebug(JoystickManagerLog) <<
this;
83 return _joystickManager();
92 _checkForAddedOrRemovedJoysticks();
93 _updatePollingTimer();
96void JoystickManager::_checkForAddedOrRemovedJoysticks()
98 qCDebug(JoystickManagerLog) <<
"Checking for added/removed joysticks, current count:" << _name2JoystickMap.size();
102 qCDebug(JoystickManagerLog) <<
"Discovery returned" << newJoystickMap.size() <<
"joysticks";
104 QString activeJoystickName;
105 if (_activeJoystick) {
106 for (
auto it = _name2JoystickMap.keyValueBegin(); it != _name2JoystickMap.keyValueEnd(); ++it) {
107 if (it->second == _activeJoystick) {
108 activeJoystickName = it->first;
114 if (_activeJoystick && (activeJoystickName.isEmpty() || !newJoystickMap.contains(activeJoystickName))) {
115 qCInfo(JoystickManagerLog) <<
"Active joystick removed:" << (activeJoystickName.isEmpty() ? QStringLiteral(
"<stale>") : activeJoystickName);
116 _setActiveJoystick(
nullptr);
121 for (QMap<QString, Joystick*>::key_value_iterator it = _name2JoystickMap.keyValueBegin(); it != _name2JoystickMap.keyValueEnd(); ++it) {
122 if (!newJoystickMap.contains(it->first)) {
123 auto key = it->first;
124 auto joystick = it->second;
125 qCInfo(JoystickManagerLog) <<
"Joystick disconnected, releasing:" << key;
126 joystick->_stopAllPolling();
128 joystick->deleteLater();
132 for (
const auto &key : newJoystickMap.keys()) {
133 if (!_name2JoystickMap.contains(key)) {
134 qCInfo(JoystickManagerLog) <<
"New joystick added:" << key;
138 _name2JoystickMap = newJoystickMap;
140 _setActiveJoystickFromSettings();
141 _updatePollingTimer();
146void JoystickManager::_setActiveJoystickFromSettings()
148 QString activeJoystickName = _joystickManagerSettings->
activeJoystickName()->rawValue().toString();
153 if (activeJoystickName.isEmpty() || !_name2JoystickMap.contains(activeJoystickName)) {
154 if (_name2JoystickMap.isEmpty()) {
158 activeJoystickName = _name2JoystickMap.first()->name();
160 qCDebug(JoystickManagerLog) <<
"Auto-selecting first available joystick:" << activeJoystickName;
163 _setActiveJoystickByName(activeJoystickName);
166Joystick *JoystickManager::activeJoystick()
168 return _activeJoystick;
171bool JoystickManager::activeJoystickEnabledForActiveVehicle()
const
173 Vehicle *activeVehicle = MultiVehicleManager::instance()->activeVehicle();
174 if (!activeVehicle || !_activeJoystick) {
177 return _joystickEnabledForVehicle(activeVehicle);
180void JoystickManager::setActiveJoystickEnabledForActiveVehicle(
bool enabled)
182 Vehicle *activeVehicle = MultiVehicleManager::instance()->activeVehicle();
184 _setJoystickEnabledForVehicle(activeVehicle, enabled);
188void JoystickManager::_setActiveJoystick(
Joystick *newActiveJoystick)
190 if (newActiveJoystick && !_name2JoystickMap.contains(newActiveJoystick->
name())) {
191 qCWarning(JoystickManagerLog) <<
"Set active not in map" << newActiveJoystick->
name();
195 if (_activeJoystick == newActiveJoystick) {
200 if (_activeJoystick) {
201 _activeJoystick->_stopAllPolling();
202 _activeJoystick =
nullptr;
206 if (newActiveJoystick) {
207 qCDebug(JoystickManagerLog) <<
"Set active:" << newActiveJoystick->
name();
209 _activeJoystick = newActiveJoystick;
211 auto multiVehicleManager = MultiVehicleManager::instance();
212 auto activeVehicle = multiVehicleManager->activeVehicle();
216 qCWarning(JoystickManagerLog) <<
"Active joystick not calibrated but enabled, cannot start polling for active vehicle. Setting joystick for vehicle to disabled.";
217 setActiveJoystickEnabledForActiveVehicle(
false);
218 }
else if (_joystickEnabledForVehicle(activeVehicle)) {
219 _activeJoystick->_startPollingForActiveVehicle();
228void JoystickManager::_setActiveJoystickByName(
const QString &name)
230 if (name.isEmpty() || !_name2JoystickMap.contains(name)) {
231 _setActiveJoystick(
nullptr);
235 _setActiveJoystick(_name2JoystickMap[name]);
238void JoystickManager::_activeVehicleChanged(
Vehicle *activeVehicle)
240 if (!_activeJoystick) {
244 _activeJoystick->_stopAllPolling();
246 if (activeVehicle && _joystickEnabledForVehicle(activeVehicle)) {
248 qCWarning(JoystickManagerLog) <<
"Active joystick not calibrated but enabled, cannot start polling for active vehicle. Setting joystick to disabled.";
249 setActiveJoystickEnabledForActiveVehicle(
false);
252 _activeJoystick->_startPollingForActiveVehicle();
258bool JoystickManager::_joystickEnabledForVehicle(
Vehicle *vehicle)
const
260 const QStringList vehicleIds = _joystickManagerSettings->
joystickEnabledVehiclesIds()->rawValue().toString().split(
",", Qt::SkipEmptyParts);
261 return vehicleIds.contains(QString::number(vehicle->
id()));
264void JoystickManager::_setJoystickEnabledForVehicle(
Vehicle *vehicle,
bool enabled)
266 QStringList vehicleIds = _joystickManagerSettings->
joystickEnabledVehiclesIds()->rawValue().toString().split(
",", Qt::SkipEmptyParts);
267 const QString vehicleIdStr = QString::number(vehicle->
id());
270 if (!vehicleIds.contains(vehicleIdStr)) {
271 vehicleIds.append(vehicleIdStr);
274 vehicleIds.removeAll(vehicleIdStr);
280void JoystickManager::_handleUpdateComplete(
int instanceId)
282 Joystick *joystick = _findJoystickByInstanceId(instanceId);
288void JoystickManager::_handleBatteryUpdated(
int instanceId)
290 Joystick *joystick = _findJoystickByInstanceId(instanceId);
292 qCDebug(JoystickManagerLog) <<
"Battery updated for" << joystick->
name();
297void JoystickManager::_handleGamepadRemapped(
int instanceId)
299 Joystick *joystick = _findJoystickByInstanceId(instanceId);
301 qCDebug(JoystickManagerLog) <<
"Gamepad remapped:" << joystick->
name();
306void JoystickManager::_handleTouchpadEvent(
int instanceId,
int touchpad,
int finger,
bool down,
float x,
float y,
float pressure)
308 Joystick *joystick = _findJoystickByInstanceId(instanceId);
310 emit joystick->
touchpadEvent(touchpad, finger, down, x, y, pressure);
314void JoystickManager::_handleSensorUpdate(
int instanceId,
int sensor,
float x,
float y,
float z)
316 Joystick *joystick = _findJoystickByInstanceId(instanceId);
318 auto *sdlJoystick = qobject_cast<JoystickBackend*>(joystick);
319 const QVector3D data(x, y, z);
321 if (sensor == 1 || sensor == 4 || sensor == 6) {
323 sdlJoystick->updateCachedAccelData(data);
327 }
else if (sensor == 2 || sensor == 5 || sensor == 7) {
329 sdlJoystick->updateCachedGyroData(data);
337Joystick *JoystickManager::_findJoystickByInstanceId(
int instanceId)
339 for (
Joystick *joystick : _name2JoystickMap) {
340 if (
auto *sdlJoystick = qobject_cast<JoystickBackend*>(joystick)) {
341 if (sdlJoystick->instanceId() == instanceId) {
349QStringList JoystickManager::linkedGroupMembers(
const QString &groupId)
const
352 if (groupId.isEmpty()) {
356 for (
auto it = _name2JoystickMap.constBegin(); it != _name2JoystickMap.constEnd(); ++it) {
357 if (it.value()->linkedGroupId() == groupId) {
358 members.append(it.key());
364Joystick *JoystickManager::joystickByName(
const QString &name)
const
366 return _name2JoystickMap.value(name,
nullptr);
369void JoystickManager::_updatePollingTimer()
371 if (!_pollTimer.isActive()) {
372 qCDebug(JoystickManagerLog) <<
"Starting SDL event pump timer";
Q_APPLICATION_STATIC(JoystickManager, _joystickManager)
#define QGC_LOGGING_CATEGORY(name, categoryStr)
static AndroidEvents * instance()
void rawValueChanged(const QVariant &value)
Fact *joystickEnabledVehiclesIds READ joystickEnabledVehiclesIds CONSTANT Fact * joystickEnabledVehiclesIds()
Fact *activeJoystickName READ activeJoystickName CONSTANT Fact * activeJoystickName()
void availableJoystickNamesChanged()
void activeJoystickChanged(Joystick *joystick)
void activeJoystickEnabledForActiveVehicleChanged()
static void shutdown(bool deleteDiscoveryCache=true)
static QMap< QString, Joystick * > discover()
Fact *calibrated READ calibrated CONSTANT Fact * calibrated()
void touchpadEvent(int touchpad, int finger, bool down, float x, float y, float pressure)
virtual bool requiresCalibration() const
void batteryStateChanged()
JoystickSettings * settings()
void accelerometerDataUpdated(const QVector3D &data)
void gyroscopeDataUpdated(const QVector3D &data)
void activeVehicleChanged(Vehicle *activeVehicle)
Provides access to all app settings.
void pumpEvents()
Pump SDL events (call periodically)