QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
JoystickManager.cc
Go to the documentation of this file.
1#include "JoystickManager.h"
2#include "Joystick.h"
3#include "Vehicle.h"
5#include "SettingsManager.h"
7#include "JoystickSDL.h"
8#include "SDLJoystick.h"
10
11#ifdef Q_OS_ANDROID
12#include "AndroidEvents.h"
13#endif
14
16
17#include <QtCore/QApplicationStatic>
18#include <QtCore/QSettings>
19#include <QtGui/QVector3D>
20
21QGC_LOGGING_CATEGORY(JoystickManagerLog, "Joystick.JoystickManager")
22
24
25JoystickManager::JoystickManager(QObject *parent)
26 : QObject(parent)
27 , _joystickManagerSettings(SettingsManager::instance()->joystickManagerSettings())
28{
29 qCDebug(JoystickManagerLog) << this;
30
31 // SDL_PumpEvents() must be called from main thread for device add/remove events
32 _pollTimer.setInterval(500);
33 (void) connect(&_pollTimer, &QTimer::timeout, this, []() {
35 });
36
37 (void) connect(_joystickManagerSettings->activeJoystickName(), &Fact::rawValueChanged, this, [this](const QVariant &value) {
38 QString joystickName = value.toString();
39 _setActiveJoystickByName(joystickName);
40 });
41
42 (void) connect(_joystickManagerSettings->joystickEnabledVehiclesIds(), &Fact::rawValueChanged, this, [this](const QVariant &value) {
43 Q_UNUSED(value);
44 auto multiVehicleManager = MultiVehicleManager::instance();
45 auto activeVehicle = multiVehicleManager->activeVehicle();
46 if (activeVehicle && _activeJoystick) {
47 if (_joystickEnabledForVehicle(activeVehicle)) {
48 _activeJoystick->_startPollingForActiveVehicle();
49 } else {
50 _activeJoystick->_stopAllPolling();
51 }
52 }
53 emit activeJoystickEnabledForActiveVehicleChanged();
54 });
55
56 (void) connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &JoystickManager::_activeVehicleChanged);
57
58#ifdef Q_OS_ANDROID
59 // Re-scan for joysticks when app resumes - devices may have connected/disconnected while backgrounded
60 (void) connect(AndroidEvents::instance(), &AndroidEvents::resumed, this, &JoystickManager::_checkForAddedOrRemovedJoysticks);
61#endif
62}
63
64JoystickManager::~JoystickManager()
65{
66 _pollTimer.stop();
67
68 for (QMap<QString, Joystick*>::key_value_iterator it = _name2JoystickMap.keyValueBegin(); it != _name2JoystickMap.keyValueEnd(); ++it) {
69 qCDebug(JoystickManagerLog) << "Releasing joystick:" << it->first;
70 it->second->stop();
71 delete it->second;
72 }
73
74 // Cache contains the same joystick instances tracked in _name2JoystickMap.
75 // We already deleted those above, so clear cache pointers only.
77
78 qCDebug(JoystickManagerLog) << this;
79}
80
81JoystickManager *JoystickManager::instance()
82{
83 return _joystickManager();
84}
85
87{
88 if (!JoystickBackend::init()) {
89 return;
90 }
91
92 _checkForAddedOrRemovedJoysticks();
93 _updatePollingTimer();
94}
95
96void JoystickManager::_checkForAddedOrRemovedJoysticks()
97{
98 qCDebug(JoystickManagerLog) << "Checking for added/removed joysticks, current count:" << _name2JoystickMap.size();
99
100 QMap<QString, Joystick*> newJoystickMap = JoystickBackend::discover();
101
102 qCDebug(JoystickManagerLog) << "Discovery returned" << newJoystickMap.size() << "joysticks";
103
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;
109 break;
110 }
111 }
112 }
113
114 if (_activeJoystick && (activeJoystickName.isEmpty() || !newJoystickMap.contains(activeJoystickName))) {
115 qCInfo(JoystickManagerLog) << "Active joystick removed:" << (activeJoystickName.isEmpty() ? QStringLiteral("<stale>") : activeJoystickName);
116 _setActiveJoystick(nullptr);
117 }
118
119 // Check to see if our current mapping contains any joysticks that are not in the new mapping
120 // If so, those joysticks have been unplugged, and need to be cleaned up
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();
127 joystick->stop();
128 joystick->deleteLater();
129 }
130 }
131
132 for (const auto &key : newJoystickMap.keys()) {
133 if (!_name2JoystickMap.contains(key)) {
134 qCInfo(JoystickManagerLog) << "New joystick added:" << key;
135 }
136 }
137
138 _name2JoystickMap = newJoystickMap;
139
140 _setActiveJoystickFromSettings();
141 _updatePollingTimer();
142
144}
145
146void JoystickManager::_setActiveJoystickFromSettings()
147{
148 QString activeJoystickName = _joystickManagerSettings->activeJoystickName()->rawValue().toString();
149
150 // Auto-select first available joystick if:
151 // - No joystick name is saved in settings, OR
152 // - Saved joystick name doesn't match any currently connected joystick
153 if (activeJoystickName.isEmpty() || !_name2JoystickMap.contains(activeJoystickName)) {
154 if (_name2JoystickMap.isEmpty()) {
155 return;
156 }
157
158 activeJoystickName = _name2JoystickMap.first()->name();
159 _joystickManagerSettings->activeJoystickName()->setRawValue(activeJoystickName);
160 qCDebug(JoystickManagerLog) << "Auto-selecting first available joystick:" << activeJoystickName;
161 }
162
163 _setActiveJoystickByName(activeJoystickName);
164}
165
166Joystick *JoystickManager::activeJoystick()
167{
168 return _activeJoystick;
169}
170
171bool JoystickManager::activeJoystickEnabledForActiveVehicle() const
172{
173 Vehicle *activeVehicle = MultiVehicleManager::instance()->activeVehicle();
174 if (!activeVehicle || !_activeJoystick) {
175 return false;
176 }
177 return _joystickEnabledForVehicle(activeVehicle);
178}
179
180void JoystickManager::setActiveJoystickEnabledForActiveVehicle(bool enabled)
181{
182 Vehicle *activeVehicle = MultiVehicleManager::instance()->activeVehicle();
183 if (activeVehicle) {
184 _setJoystickEnabledForVehicle(activeVehicle, enabled);
185 }
186}
187
188void JoystickManager::_setActiveJoystick(Joystick *newActiveJoystick)
189{
190 if (newActiveJoystick && !_name2JoystickMap.contains(newActiveJoystick->name())) {
191 qCWarning(JoystickManagerLog) << "Set active not in map" << newActiveJoystick->name();
192 return;
193 }
194
195 if (_activeJoystick == newActiveJoystick) {
196 return;
197 }
198
199 // Cleanup old active joystick
200 if (_activeJoystick) {
201 _activeJoystick->_stopAllPolling();
202 _activeJoystick = nullptr;
203 emit activeJoystickChanged(nullptr);
204 }
205
206 if (newActiveJoystick) {
207 qCDebug(JoystickManagerLog) << "Set active:" << newActiveJoystick->name();
208
209 _activeJoystick = newActiveJoystick;
210
211 auto multiVehicleManager = MultiVehicleManager::instance();
212 auto activeVehicle = multiVehicleManager->activeVehicle();
213
214 if (activeVehicle) {
215 if (_activeJoystick->requiresCalibration() && _joystickEnabledForVehicle(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();
220 }
221 }
222
223 emit activeJoystickChanged(_activeJoystick);
225 }
226}
227
228void JoystickManager::_setActiveJoystickByName(const QString &name)
229{
230 if (name.isEmpty() || !_name2JoystickMap.contains(name)) {
231 _setActiveJoystick(nullptr);
232 return;
233 }
234
235 _setActiveJoystick(_name2JoystickMap[name]);
236}
237
238void JoystickManager::_activeVehicleChanged(Vehicle *activeVehicle)
239{
240 if (!_activeJoystick) {
241 return;
242 }
243
244 _activeJoystick->_stopAllPolling();
245
246 if (activeVehicle && _joystickEnabledForVehicle(activeVehicle)) {
247 if (!_activeJoystick->settings()->calibrated()->rawValue().toBool()) {
248 qCWarning(JoystickManagerLog) << "Active joystick not calibrated but enabled, cannot start polling for active vehicle. Setting joystick to disabled.";
249 setActiveJoystickEnabledForActiveVehicle(false);
250 return;
251 }
252 _activeJoystick->_startPollingForActiveVehicle();
253 }
254
256}
257
258bool JoystickManager::_joystickEnabledForVehicle(Vehicle *vehicle) const
259{
260 const QStringList vehicleIds = _joystickManagerSettings->joystickEnabledVehiclesIds()->rawValue().toString().split(",", Qt::SkipEmptyParts);
261 return vehicleIds.contains(QString::number(vehicle->id()));
262}
263
264void JoystickManager::_setJoystickEnabledForVehicle(Vehicle *vehicle, bool enabled)
265{
266 QStringList vehicleIds = _joystickManagerSettings->joystickEnabledVehiclesIds()->rawValue().toString().split(",", Qt::SkipEmptyParts);
267 const QString vehicleIdStr = QString::number(vehicle->id());
268
269 if (enabled) {
270 if (!vehicleIds.contains(vehicleIdStr)) {
271 vehicleIds.append(vehicleIdStr);
272 }
273 } else {
274 vehicleIds.removeAll(vehicleIdStr);
275 }
276
277 _joystickManagerSettings->joystickEnabledVehiclesIds()->setRawValue(vehicleIds.join(","));
278}
279
280void JoystickManager::_handleUpdateComplete(int instanceId)
281{
282 Joystick *joystick = _findJoystickByInstanceId(instanceId);
283 if (joystick) {
284 emit joystick->updateComplete();
285 }
286}
287
288void JoystickManager::_handleBatteryUpdated(int instanceId)
289{
290 Joystick *joystick = _findJoystickByInstanceId(instanceId);
291 if (joystick) {
292 qCDebug(JoystickManagerLog) << "Battery updated for" << joystick->name();
293 emit joystick->batteryStateChanged();
294 }
295}
296
297void JoystickManager::_handleGamepadRemapped(int instanceId)
298{
299 Joystick *joystick = _findJoystickByInstanceId(instanceId);
300 if (joystick) {
301 qCDebug(JoystickManagerLog) << "Gamepad remapped:" << joystick->name();
302 emit joystick->mappingRemapped();
303 }
304}
305
306void JoystickManager::_handleTouchpadEvent(int instanceId, int touchpad, int finger, bool down, float x, float y, float pressure)
307{
308 Joystick *joystick = _findJoystickByInstanceId(instanceId);
309 if (joystick) {
310 emit joystick->touchpadEvent(touchpad, finger, down, x, y, pressure);
311 }
312}
313
314void JoystickManager::_handleSensorUpdate(int instanceId, int sensor, float x, float y, float z)
315{
316 Joystick *joystick = _findJoystickByInstanceId(instanceId);
317 if (joystick) {
318 auto *sdlJoystick = qobject_cast<JoystickBackend*>(joystick);
319 const QVector3D data(x, y, z);
320 // SDL_SENSOR_ACCEL = 1, SDL_SENSOR_GYRO = 2
321 if (sensor == 1 || sensor == 4 || sensor == 6) { // ACCEL, ACCEL_L, ACCEL_R
322 if (sdlJoystick) {
323 sdlJoystick->updateCachedAccelData(data);
324 } else {
325 emit joystick->accelerometerDataUpdated(data);
326 }
327 } else if (sensor == 2 || sensor == 5 || sensor == 7) { // GYRO, GYRO_L, GYRO_R
328 if (sdlJoystick) {
329 sdlJoystick->updateCachedGyroData(data);
330 } else {
331 emit joystick->gyroscopeDataUpdated(data);
332 }
333 }
334 }
335}
336
337Joystick *JoystickManager::_findJoystickByInstanceId(int instanceId)
338{
339 for (Joystick *joystick : _name2JoystickMap) {
340 if (auto *sdlJoystick = qobject_cast<JoystickBackend*>(joystick)) {
341 if (sdlJoystick->instanceId() == instanceId) {
342 return joystick;
343 }
344 }
345 }
346 return nullptr;
347}
348
349QStringList JoystickManager::linkedGroupMembers(const QString &groupId) const
350{
351 QStringList members;
352 if (groupId.isEmpty()) {
353 return members;
354 }
355
356 for (auto it = _name2JoystickMap.constBegin(); it != _name2JoystickMap.constEnd(); ++it) {
357 if (it.value()->linkedGroupId() == groupId) {
358 members.append(it.key());
359 }
360 }
361 return members;
362}
363
364Joystick *JoystickManager::joystickByName(const QString &name) const
365{
366 return _name2JoystickMap.value(name, nullptr);
367}
368
369void JoystickManager::_updatePollingTimer()
370{
371 if (!_pollTimer.isActive()) {
372 qCDebug(JoystickManagerLog) << "Starting SDL event pump timer";
373 _pollTimer.start();
374 }
375}
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 bool init()
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
Definition Joystick.h:201
QString name() const
Definition Joystick.h:198
void mappingRemapped()
void batteryStateChanged()
void updateComplete()
JoystickSettings * settings()
Definition Joystick.h:197
void accelerometerDataUpdated(const QVector3D &data)
void gyroscopeDataUpdated(const QVector3D &data)
void activeVehicleChanged(Vehicle *activeVehicle)
Provides access to all app settings.
int id() const
Definition Vehicle.h:425
void pumpEvents()
Pump SDL events (call periodically)