QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
Joystick.cc
Go to the documentation of this file.
1#include "Joystick.h"
2#include "Fact.h"
3#include "MavlinkAction.h"
6#include "FirmwarePlugin.h"
7#include "GimbalController.h"
8#include "QGCCorePlugin.h"
10#include "QmlObjectListModel.h"
11#include "SettingsManager.h"
12#include "Vehicle.h"
13#include "VehicleSupports.h"
14#include "JoystickManager.h"
15#include "MultiVehicleManager.h"
16
17#include <QtCore/QCoreApplication>
18#include <QtCore/QSet>
19#include <algorithm>
20#include <cmath>
21#include <QtCore/QSettings>
22#include <QtCore/QThread>
23
24QGC_LOGGING_CATEGORY(JoystickLog, "Joystick.Joystick")
25QGC_LOGGING_CATEGORY(JoystickVerboseLog, "Joystick.Joystick:verbose")
26
27static QDebug operator<<(QDebug debug, Joystick::ButtonEvent_t event)
28{
29 switch (event) {
30 case Joystick::ButtonEventDownTransition: return debug << "Down";
31 case Joystick::ButtonEventUpTransition: return debug << "Up";
32 case Joystick::ButtonEventRepeat: return debug << "Repeat";
33 case Joystick::ButtonEventNone: return debug << "None";
34 }
35 return debug << static_cast<int>(event);
36}
37
38namespace
39{
40static constexpr const char* kButtonActionArrayGroup = "JoystickButtonActionSettingsArray";
41static constexpr const char* kButtonActionNameKey = "actionName";
42static constexpr const char* kButtonRepeatKey = "repeat";
43static constexpr const char* kAxisSettingsArrayGroup = "JoystickAxisSettingsArray";
44static constexpr const char* kAxisFunctionKey = "function";
45static constexpr const char* kAxisMinKey = "min";
46static constexpr const char* kAxisMaxKey = "max";
47static constexpr const char* kAxisCenterKey = "center";
48static constexpr const char* kAxisDeadbandKey = "deadband";
49static constexpr const char* kAxisReversedKey = "reversed";
50}
51
52/*===========================================================================*/
53
54AssignedButtonAction::AssignedButtonAction(const QString &actionName_, bool repeat_)
55 : actionName(actionName_)
56 , repeat(repeat_)
57{
58 qCDebug(JoystickVerboseLog) << this;
59}
60
61AvailableButtonAction::AvailableButtonAction(const QString &actionName_, std::function<void()> onDown_, std::function<void()> onUp_, std::function<void()> onRepeat_, QObject *parent)
62 : QObject(parent)
63 , _actionName(actionName_)
64 , _onDown(std::move(onDown_))
65 , _onRepeat(std::move(onRepeat_))
66 , _onUp(std::move(onUp_))
67{
68 qCDebug(JoystickVerboseLog) << this;
69}
70
71/*===========================================================================*/
72
73Joystick::Joystick(const QString &name, int axisCount, int buttonCount, int hatCount, QObject *parent)
74 : QThread(parent)
75 , _name(name)
76 , _axisCount(axisCount)
77 , _buttonCount(buttonCount)
78 , _hatCount(hatCount)
79 , _hatButtonCount(4 * hatCount)
80 , _totalButtonCount(_buttonCount + _hatButtonCount)
81 , _rgCalibration(_axisCount)
82 , _buttonEventStates(_totalButtonCount)
83 , _assignedButtonActions(_totalButtonCount, nullptr)
84 , _mavlinkActionManager(new MavlinkActionManager(SettingsManager::instance()->mavlinkActionsSettings()->joystickActionsFile(), this))
85 , _availableButtonActions(new QmlObjectListModel(this))
86 , _joystickManager(JoystickManager::instance())
87 , _joystickSettings(name, _axisCount, _totalButtonCount)
88{
89 qCDebug(JoystickLog)
90 << name
91 << "axisCount:" << axisCount
92 << "buttonCount:" << buttonCount
93 << "hatCount:" << hatCount
94 << this;
95
96 if (QCoreApplication *const app = QCoreApplication::instance()) {
97 QThread *const guiThread = app->thread();
98 if (_joystickSettings.thread() != guiThread) {
99 _joystickSettings.moveToThread(guiThread);
100 }
101
102 const auto ensureFactThread = [guiThread](Fact *fact) {
103 if (fact && fact->thread() != guiThread) {
104 fact->moveToThread(guiThread);
105 }
106 };
107
108 ensureFactThread(_joystickSettings.calibrated());
109 ensureFactThread(_joystickSettings.circleCorrection());
110 ensureFactThread(_joystickSettings.useDeadband());
111 ensureFactThread(_joystickSettings.negativeThrust());
112 ensureFactThread(_joystickSettings.throttleSmoothing());
113 ensureFactThread(_joystickSettings.axisFrequencyHz());
114 ensureFactThread(_joystickSettings.buttonFrequencyHz());
115 ensureFactThread(_joystickSettings.throttleModeCenterZero());
116 ensureFactThread(_joystickSettings.transmitterMode());
117 ensureFactThread(_joystickSettings.exponentialPct());
118 ensureFactThread(_joystickSettings.enableManualControlPitchExtension());
119 ensureFactThread(_joystickSettings.enableManualControlRollExtension());
120 ensureFactThread(_joystickSettings.enableAdditionalAxis1());
121 ensureFactThread(_joystickSettings.enableAdditionalAxis2());
122 ensureFactThread(_joystickSettings.enableAdditionalAxis3());
123 ensureFactThread(_joystickSettings.enableAdditionalAxis4());
124 ensureFactThread(_joystickSettings.enableAdditionalAxis5());
125 ensureFactThread(_joystickSettings.enableAdditionalAxis6());
126 ensureFactThread(_joystickSettings.additionalAxesFunction());
127 }
128
129 // Changes to manual control extension settings require re-calibration
130 connect(_joystickSettings.enableManualControlPitchExtension(), &Fact::rawValueChanged, this, [this]() {
131 _joystickSettings.calibrated()->setRawValue(false);
132 });
133 connect(_joystickSettings.enableManualControlRollExtension(), &Fact::rawValueChanged, this, [this]() {
134 _joystickSettings.calibrated()->setRawValue(false);
135 });
136 connect(_joystickSettings.enableAdditionalAxis1(), &Fact::rawValueChanged, this, [this]() {
137 _joystickSettings.calibrated()->setRawValue(false);
138 });
139 connect(_joystickSettings.enableAdditionalAxis2(), &Fact::rawValueChanged, this, [this]() {
140 _joystickSettings.calibrated()->setRawValue(false);
141 });
142 connect(_joystickSettings.enableAdditionalAxis3(), &Fact::rawValueChanged, this, [this]() {
143 _joystickSettings.calibrated()->setRawValue(false);
144 });
145 connect(_joystickSettings.enableAdditionalAxis4(), &Fact::rawValueChanged, this, [this]() {
146 _joystickSettings.calibrated()->setRawValue(false);
147 });
148 connect(_joystickSettings.enableAdditionalAxis5(), &Fact::rawValueChanged, this, [this]() {
149 _joystickSettings.calibrated()->setRawValue(false);
150 });
151 connect(_joystickSettings.enableAdditionalAxis6(), &Fact::rawValueChanged, this, [this]() {
152 _joystickSettings.calibrated()->setRawValue(false);
153 });
154
155 _resetFunctionToAxisMap();
156 _resetAxisCalibrationData();
157 _resetButtonActionData();
158 _resetButtonEventStates();
159
160 _buildAvailableButtonsActionList(MultiVehicleManager::instance()->activeVehicle());
161
162 _loadFromSettingsIntoCalibrationData();
163}
164
166{
167 _exitPollingThread = true;
168 if (isRunning()) {
169 if (QThread::currentThread() == this) {
170 qCWarning(JoystickLog) << "Skipping wait() on joystick thread";
171 } else {
172 wait();
173 }
174 }
175
176 _resetButtonActionData();
177 _availableButtonActions->clearAndDeleteContents();
178}
179
180void Joystick::_resetFunctionToAxisMap()
181{
182 _axisFunctionToJoystickAxisMap.clear();
183 for (int i = 0; i < maxAxisFunction; i++) {
184 _axisFunctionToJoystickAxisMap[static_cast<AxisFunction_t>(i)] = kJoystickAxisNotAssigned;
185 }
186}
187
188void Joystick::_resetAxisCalibrationData()
189{
190 _resetFunctionToAxisMap();
191 for (int axis = 0; axis < _axisCount; axis++) {
192 auto& calibration = _rgCalibration[axis];
193 calibration.reset();
194 }
195}
196
197void Joystick::_resetButtonActionData()
198{
199 for (int i = 0; i < _assignedButtonActions.count(); i++) {
200 delete _assignedButtonActions[i];
201 _assignedButtonActions[i] = nullptr;
202 }
203}
204
205void Joystick::_resetButtonEventStates()
206{
207 for (int i = 0; i < _buttonEventStates.count(); i++) {
208 _buttonEventStates[i] = ButtonEventNone;
209 }
210}
211
212void Joystick::_loadButtonSettings()
213{
214 const QString actionNameKey = QString::fromLatin1(kButtonActionNameKey);
215 const QString repeatKey = QString::fromLatin1(kButtonRepeatKey);
216
217 QSettings buttonSettings;
218 buttonSettings.beginGroup(_joystickSettings.settingsGroup());
219
220 if (buttonSettings.childGroups().contains(QString::fromLatin1(kButtonActionArrayGroup))) {
221 buttonSettings.beginGroup(QString::fromLatin1(kButtonActionArrayGroup));
222
223 qCDebug(JoystickLog) << "Button Actions:";
224
225 bool foundButton = false;
226 for (int buttonIndex = 0; buttonIndex < _totalButtonCount; buttonIndex++) {
227 if (!buttonSettings.childGroups().contains(QString::number(buttonIndex))) {
228 continue;
229 }
230
231 buttonSettings.beginGroup(QString::number(buttonIndex));
232 const QString actionName = buttonSettings.value(actionNameKey).toString();
233 const bool repeat = buttonSettings.value(repeatKey, false).toBool();
234 buttonSettings.endGroup();
235
236 if (actionName.isEmpty()) {
237 qCWarning(JoystickLog)
238 << " "
239 << "button:" << buttonIndex
240 << "has empty action name, clearing action from data";
241 buttonSettings.remove(QString::number(buttonIndex));
242 continue;
243 }
244 if (_findAvailableButtonActionIndex(actionName) == -1) {
245 qCWarning(JoystickLog)
246 << " "
247 << "button:" << buttonIndex
248 << "has unknown action name:" << actionName
249 << ", clearing action from data";
250 buttonSettings.remove(QString::number(buttonIndex));
251 continue;
252 }
253 if (actionName == _buttonActionNone) {
254 buttonSettings.remove(QString::number(buttonIndex));
255 continue;
256 }
257
258 AssignedButtonAction *buttonAction = new AssignedButtonAction(actionName, repeat);
259 _assignedButtonActions[buttonIndex] = buttonAction;
260 _assignedButtonActions[buttonIndex]->buttonElapsedTimer.start();
261 foundButton = true;
262
263 qCDebug(JoystickLog)
264 << " "
265 << "button:" << buttonIndex
266 << "actionName:" << actionName
267 << "repeat:" << repeat;
268 }
269
270 buttonSettings.endGroup();
271
272 if (!foundButton) {
273 buttonSettings.remove(QString::fromLatin1(kButtonActionArrayGroup));
274 }
275 }
276}
277
278void Joystick::_foundInvalidAxisSettingsCleanup()
279{
280 _clearAxisSettings();
281 _resetAxisCalibrationData();
282 _joystickSettings.calibrated()->setRawValue(false);
283}
284
285void Joystick::_loadAxisSettings(bool joystickCalibrated, int transmitterMode)
286{
287 QSettings axisSettings;
288 axisSettings.beginGroup(_joystickSettings.settingsGroup());
289
290 // If the joystick isn't calibrated, we skip loading calibration data.
291 // Also there shouldn't be stored axis information, so clear that if any
292 if (!joystickCalibrated) {
293 _clearAxisSettings();
294 _resetAxisCalibrationData();
295 return;
296 }
297
298 const QString functionKey = QString::fromLatin1(kAxisFunctionKey);
299 const QString minKey = QString::fromLatin1(kAxisMinKey);
300 const QString maxKey = QString::fromLatin1(kAxisMaxKey);
301 const QString centerKey = QString::fromLatin1(kAxisCenterKey);
302 const QString deadbandKey = QString::fromLatin1(kAxisDeadbandKey);
303 const QString reversedKey = QString::fromLatin1(kAxisReversedKey);
304
305 qCDebug(JoystickLog) << "Axis Settings:";
306
307 axisSettings.beginGroup(QString::fromLatin1(kAxisSettingsArrayGroup));
308 for (int axis = 0; axis < _axisCount; axis++) {
309 if (!axisSettings.childGroups().contains(QString::number(axis))) {
310 qCDebug(JoystickLog)
311 << " "
312 << "axis:" << axis
313 << "no settings found, skipping";
314 continue;
315 }
316
317 axisSettings.beginGroup(QString::number(axis));
318
319 auto& axisCalibration = _rgCalibration[axis];
320
321 const int axisFunction = axisSettings.value(functionKey, maxAxisFunction).toInt();
322 if (axisFunction < 0 || axisFunction > maxAxisFunction) {
323 qCWarning(JoystickLog) << "Invalid function" << axisFunction << "for axis" << axis;
324 axisSettings.endGroup();
325 continue;
326 }
327 if (axisFunction == maxAxisFunction) {
328 // Older code would save unassigned axes with maxAxisFunction, we now skip loading those since that is not a valid function assignment
329 axisSettings.endGroup();
330 continue;
331 }
332 _setJoystickAxisForAxisFunction(static_cast<AxisFunction_t>(axisFunction), axis);
333
334 axisCalibration.center = axisSettings.value(centerKey, axisCalibration.center).toInt();
335 axisCalibration.min = axisSettings.value(minKey, axisCalibration.min).toInt();
336 axisCalibration.max = axisSettings.value(maxKey, axisCalibration.max).toInt();
337 axisCalibration.deadband = axisSettings.value(deadbandKey, axisCalibration.deadband).toInt();
338 axisCalibration.reversed = axisSettings.value(reversedKey, axisCalibration.reversed).toBool();
339
340 qCDebug(JoystickLog)
341 << " "
342 << "axis:" << axis
343 << "min:" << axisCalibration.min
344 << "max:" << axisCalibration.max
345 << "center:" << axisCalibration.center
346 << "reversed:" << axisCalibration.reversed
347 << "deadband:" << axisCalibration.deadband
348 << "axisFunction:" << axisFunctionToString(static_cast<AxisFunction_t>(axisFunction));
349
350 axisSettings.endGroup();
351 }
352 axisSettings.endGroup();
353
354 // All axis information is loaded, verify that we have all the required control mappings
355 bool rollFunctionNotAssigned = _axisFunctionToJoystickAxisMap[rollFunction] == kJoystickAxisNotAssigned;
356 if (rollFunctionNotAssigned) {
357 qCWarning(JoystickLog) << "Roll axis function not assigned";
358 }
359 bool pitchFunctionNotAssigned = _axisFunctionToJoystickAxisMap[pitchFunction] == kJoystickAxisNotAssigned;
360 if (pitchFunctionNotAssigned) {
361 qCWarning(JoystickLog) << "Pitch axis function not assigned";
362 }
363 bool yawFunctionNotAssigned = _axisFunctionToJoystickAxisMap[yawFunction] == kJoystickAxisNotAssigned;
364 if (yawFunctionNotAssigned) {
365 qCWarning(JoystickLog) << "Yaw axis function not assigned";
366 }
367 bool throttleFunctionNotAssigned = _axisFunctionToJoystickAxisMap[throttleFunction] == kJoystickAxisNotAssigned;
368 if (throttleFunctionNotAssigned) {
369 qCWarning(JoystickLog) << "Throttle axis function not assigned";
370 }
371 bool pitchExtensionFunctionRequiredButNotAssigned = false;
372 if (_joystickSettings.enableManualControlPitchExtension()->rawValue().toBool()) {
373 pitchExtensionFunctionRequiredButNotAssigned = _getJoystickAxisForAxisFunction(pitchExtensionFunction) == kJoystickAxisNotAssigned;
374 if (pitchExtensionFunctionRequiredButNotAssigned) {
375 qCWarning(JoystickLog) << "Internal Error: Missing pitch extension axis function mapping!";
376 }
377 }
378 bool rollExtensionFunctionRequiredButNotAssigned = false;
379 if (_joystickSettings.enableManualControlRollExtension()->rawValue().toBool()) {
380 rollExtensionFunctionRequiredButNotAssigned = _getJoystickAxisForAxisFunction(rollExtensionFunction) == kJoystickAxisNotAssigned;
381 if (rollExtensionFunctionRequiredButNotAssigned) {
382 qCWarning(JoystickLog) << "Internal Error: Missing roll extension axis function mapping!";
383 }
384 }
385 bool additionalAxis1FunctionRequiredButNotAssigned = false;
386 if (_joystickSettings.enableAdditionalAxis1()->rawValue().toBool()) {
387 additionalAxis1FunctionRequiredButNotAssigned = _getJoystickAxisForAxisFunction(additionalAxis1Function) == kJoystickAxisNotAssigned;
388 if (additionalAxis1FunctionRequiredButNotAssigned) {
389 qCWarning(JoystickLog) << "Internal Error: Missing additional axis 1 function mapping!";
390 }
391 }
392 bool additionalAxis2FunctionRequiredButNotAssigned = false;
393 if (_joystickSettings.enableAdditionalAxis2()->rawValue().toBool()) {
394 additionalAxis2FunctionRequiredButNotAssigned = _getJoystickAxisForAxisFunction(additionalAxis2Function) == kJoystickAxisNotAssigned;
395 if (additionalAxis2FunctionRequiredButNotAssigned) {
396 qCWarning(JoystickLog) << "Internal Error: Missing additional axis 2 function mapping!";
397 }
398 }
399 bool additionalAxis3FunctionRequiredButNotAssigned = false;
400 if (_joystickSettings.enableAdditionalAxis3()->rawValue().toBool()) {
401 additionalAxis3FunctionRequiredButNotAssigned = _getJoystickAxisForAxisFunction(additionalAxis3Function) == kJoystickAxisNotAssigned;
402 if (additionalAxis3FunctionRequiredButNotAssigned) {
403 qCWarning(JoystickLog) << "Internal Error: Missing additional axis 3 function mapping!";
404 }
405 }
406 bool additionalAxis4FunctionRequiredButNotAssigned = false;
407 if (_joystickSettings.enableAdditionalAxis4()->rawValue().toBool()) {
408 additionalAxis4FunctionRequiredButNotAssigned = _getJoystickAxisForAxisFunction(additionalAxis4Function) == kJoystickAxisNotAssigned;
409 if (additionalAxis4FunctionRequiredButNotAssigned) {
410 qCWarning(JoystickLog) << "Internal Error: Missing additional axis 4 function mapping!";
411 }
412 }
413 bool additionalAxis5FunctionRequiredButNotAssigned = false;
414 if (_joystickSettings.enableAdditionalAxis5()->rawValue().toBool()) {
415 additionalAxis5FunctionRequiredButNotAssigned = _getJoystickAxisForAxisFunction(additionalAxis5Function) == kJoystickAxisNotAssigned;
416 if (additionalAxis5FunctionRequiredButNotAssigned) {
417 qCWarning(JoystickLog) << "Internal Error: Missing additional axis 5 function mapping!";
418 }
419 }
420 bool additionalAxis6FunctionRequiredButNotAssigned = false;
421 if (_joystickSettings.enableAdditionalAxis6()->rawValue().toBool()) {
422 additionalAxis6FunctionRequiredButNotAssigned = _getJoystickAxisForAxisFunction(additionalAxis6Function) == kJoystickAxisNotAssigned;
423 if (additionalAxis6FunctionRequiredButNotAssigned) {
424 qCWarning(JoystickLog) << "Internal Error: Missing additional axis 6 function mapping!";
425 }
426 }
427 if (rollFunctionNotAssigned || pitchFunctionNotAssigned || yawFunctionNotAssigned || throttleFunctionNotAssigned ||
428 pitchExtensionFunctionRequiredButNotAssigned || rollExtensionFunctionRequiredButNotAssigned ||
429 additionalAxis1FunctionRequiredButNotAssigned || additionalAxis2FunctionRequiredButNotAssigned || additionalAxis3FunctionRequiredButNotAssigned ||
430 additionalAxis4FunctionRequiredButNotAssigned || additionalAxis5FunctionRequiredButNotAssigned || additionalAxis6FunctionRequiredButNotAssigned) {
431 qCWarning(JoystickLog) << "Missing control axis function(s), resetting all axis settings, marking joystick as uncalibrated and disabled";
432 _resetAxisCalibrationData();
433 _clearAxisSettings();
434 _joystickSettings.calibrated()->setRawValue(false);
435 _joystickManager->setActiveJoystickEnabledForActiveVehicle(false);
436 return;
437 }
438
439 // FunctionAxis mappings are always stored in TX mode 2
440 // Remap to stored TX mode in settings for UI display
441 _remapFunctionsInFunctionMapToNewTransmittedMode(2, transmitterMode);
442}
443
444void Joystick::_loadFromSettingsIntoCalibrationData()
445{
446 _resetAxisCalibrationData();
447 _resetButtonActionData();
448
449 // Top level joystick settings come through the JoystickSettings SettingsGroup
450
451 bool calibrated = _joystickSettings.calibrated()->rawValue().toBool();
452 int transmitterMode = _joystickSettings.transmitterMode()->rawValue().toInt();
453
454 qCDebug(JoystickLog) << name();
455 qCDebug(JoystickLog) << " calibrated:" << _joystickSettings.calibrated()->rawValue().toBool();
456 qCDebug(JoystickLog) << " throttleSmoothing:" << _joystickSettings.throttleSmoothing()->rawValue().toBool();
457 qCDebug(JoystickLog) << " axisFrequencyHz:" << _joystickSettings.axisFrequencyHz()->rawValue().toDouble();
458 qCDebug(JoystickLog) << " buttonFrequencyHz:" << _joystickSettings.buttonFrequencyHz()->rawValue().toDouble();
459 qCDebug(JoystickLog) << " throttleModeCenterZero:" << _joystickSettings.throttleModeCenterZero()->rawValue().toBool();
460 qCDebug(JoystickLog) << " negativeThrust:" << _joystickSettings.negativeThrust()->rawValue().toBool();
461 qCDebug(JoystickLog) << " circleCorrection:" << _joystickSettings.circleCorrection()->rawValue().toBool();
462 qCDebug(JoystickLog) << " exponentialPct:" << _joystickSettings.exponentialPct()->rawValue().toDouble();
463 qCDebug(JoystickLog) << " useDeadband:" << _joystickSettings.useDeadband()->rawValue().toBool();
464 qCDebug(JoystickLog) << " transmitterMode:" << transmitterMode;
465 qCDebug(JoystickLog) << " enableManualControlPitchExtension:" << _joystickSettings.enableManualControlPitchExtension()->rawValue().toBool();
466 qCDebug(JoystickLog) << " enableManualControlRollExtension:" << _joystickSettings.enableManualControlRollExtension()->rawValue().toBool();
467 qCDebug(JoystickLog) << " additionalAxesFunction:" << (_joystickSettings.additionalAxesFunction()->rawValue().toUInt() == 1 ? "RC_CHANNELS_OVERRIDE" : "MANUAL_CONTROL");
468 qCDebug(JoystickLog) << " enableAdditionalAxis1:" << _joystickSettings.enableAdditionalAxis1()->rawValue().toBool();
469 qCDebug(JoystickLog) << " enableAdditionalAxis2:" << _joystickSettings.enableAdditionalAxis2()->rawValue().toBool();
470 qCDebug(JoystickLog) << " enableAdditionalAxis3:" << _joystickSettings.enableAdditionalAxis3()->rawValue().toBool();
471 qCDebug(JoystickLog) << " enableAdditionalAxis4:" << _joystickSettings.enableAdditionalAxis4()->rawValue().toBool();
472 qCDebug(JoystickLog) << " enableAdditionalAxis5:" << _joystickSettings.enableAdditionalAxis5()->rawValue().toBool();
473 qCDebug(JoystickLog) << " enableAdditionalAxis6:" << _joystickSettings.enableAdditionalAxis6()->rawValue().toBool();
474
475 _loadAxisSettings(calibrated, transmitterMode);
476 _loadButtonSettings();
477}
478
479void Joystick::_saveAxisSettings(int transmitterMode)
480{
481 qCDebug(JoystickLog) << name();
482
483 // FunctionAxis mappings are always stored in TX mode 2
484 // Temporarily remap from calibration TX mode to mode 2 for storage
485 _remapFunctionsInFunctionMapToNewTransmittedMode(transmitterMode, 2);
486
487 QSettings axisSettings;
488 axisSettings.beginGroup(_joystickSettings.settingsGroup());
489 axisSettings.beginGroup(QString::fromLatin1(kAxisSettingsArrayGroup));
490
491 const QString functionKey = QString::fromLatin1(kAxisFunctionKey);
492 const QString minKey = QString::fromLatin1(kAxisMinKey);
493 const QString maxKey = QString::fromLatin1(kAxisMaxKey);
494 const QString centerKey = QString::fromLatin1(kAxisCenterKey);
495 const QString deadbandKey = QString::fromLatin1(kAxisDeadbandKey);
496 const QString reversedKey = QString::fromLatin1(kAxisReversedKey);
497
498 for (int axis = 0; axis < _axisCount; axis++) {
499 AxisFunction_t function = _getAxisFunctionForJoystickAxis(axis);
500 if (function == maxAxisFunction) {
501 // No function assigned to axis, nothing to save
502 continue;
503 }
504 AxisCalibration_t *const calibration = &_rgCalibration[axis];
505 axisSettings.beginGroup(QString::number(axis));
506
507 axisSettings.setValue(centerKey, calibration->center);
508 axisSettings.setValue(minKey, calibration->min);
509 axisSettings.setValue(maxKey, calibration->max);
510 axisSettings.setValue(deadbandKey, calibration->deadband);
511 axisSettings.setValue(reversedKey, calibration->reversed);
512 axisSettings.setValue(functionKey, static_cast<int>(function));
513
514 qCDebug(JoystickLog)
515 << " "
516 << "axis:" << axis
517 << "min:" << calibration->min
518 << "max:" << calibration->max
519 << "center:" << calibration->center
520 << "reversed:" << calibration->reversed
521 << "deadband:" << calibration->deadband
522 << "axisFunction:" << axisFunctionToString(function);
523
524 axisSettings.endGroup();
525 }
526
527 axisSettings.endGroup();
528 axisSettings.endGroup();
529
530 // Map back to current TX mode
531 _remapFunctionsInFunctionMapToNewTransmittedMode(2, transmitterMode);
532}
533
534void Joystick::_saveButtonSettings()
535{
536 qCDebug(JoystickLog) << name();
537
538 const QString actionNameKey = QString::fromLatin1(kButtonActionNameKey);
539 const QString repeatKey = QString::fromLatin1(kButtonRepeatKey);
540
541 QSettings buttonSettings;
542 buttonSettings.beginGroup(_joystickSettings.settingsGroup());
543 buttonSettings.beginGroup(QString::fromLatin1(kButtonActionArrayGroup));
544
545 bool anyButtonsSaved = false;
546 for (int buttonIndex = 0; buttonIndex < _totalButtonCount; buttonIndex++) {
547 AssignedButtonAction *buttonAction = _assignedButtonActions[buttonIndex];
548
549 if (buttonAction) {
550 buttonSettings.beginGroup(QString::number(buttonIndex));
551 buttonSettings.setValue(actionNameKey, buttonAction->actionName);
552 buttonSettings.setValue(repeatKey, buttonAction->repeat);
553 buttonSettings.endGroup();
554
555 anyButtonsSaved = true;
556
557 qCDebug(JoystickLog)
558 << " "
559 << "button:" << buttonIndex
560 << "actionName:" << buttonAction->actionName
561 << "repeat:" << buttonAction->repeat;
562 } else {
563 // No action assigned, remove any existing settings
564 buttonSettings.remove(QString::number(buttonIndex));
565 }
566 }
567
568 buttonSettings.endGroup();
569 buttonSettings.endGroup();
570
571 if (!anyButtonsSaved) {
572 qCDebug(JoystickLog) << " No button actions to save, cleared button action settings.";
573 _clearButtonSettings();
574 }
575}
576
577void Joystick::_clearAxisSettings()
578{
579 QSettings axisSettings;
580 axisSettings.beginGroup(_joystickSettings.settingsGroup());
581 axisSettings.remove(QString::fromLatin1(kAxisSettingsArrayGroup));
582 axisSettings.endGroup();
583}
584
585void Joystick::_clearButtonSettings()
586{
587 QSettings buttonSettings;
588 buttonSettings.beginGroup(_joystickSettings.settingsGroup());
589 buttonSettings.remove(QString::fromLatin1(kButtonActionArrayGroup));
590 buttonSettings.endGroup();
591}
592
593void Joystick::_saveFromCalibrationDataIntoSettings()
594{
595 bool calibrated = _joystickSettings.calibrated()->rawValue().toBool();
596 int transmitterMode = _joystickSettings.transmitterMode()->rawValue().toInt();
597
598 qCDebug(JoystickLog) << name();
599 qCDebug(JoystickLog) << " calibrated:" << calibrated;
600 qCDebug(JoystickLog) << " throttleSmoothing:" << _joystickSettings.throttleSmoothing()->rawValue().toBool();
601 qCDebug(JoystickLog) << " axisFrequencyHz:" << _joystickSettings.axisFrequencyHz()->rawValue().toDouble();
602 qCDebug(JoystickLog) << " buttonFrequencyHz:" << _joystickSettings.buttonFrequencyHz()->rawValue().toDouble();
603 qCDebug(JoystickLog) << " throttleModeCenterZero:" << _joystickSettings.throttleModeCenterZero()->rawValue().toBool();
604 qCDebug(JoystickLog) << " negativeThrust:" << _joystickSettings.negativeThrust()->rawValue().toBool();
605 qCDebug(JoystickLog) << " circleCorrection:" << _joystickSettings.circleCorrection()->rawValue().toBool();
606 qCDebug(JoystickLog) << " exponentialPct:" << _joystickSettings.exponentialPct()->rawValue().toDouble();
607 qCDebug(JoystickLog) << " useDeadband:" << _joystickSettings.useDeadband()->rawValue().toBool();
608 qCDebug(JoystickLog) << " enableManualControlPitchExtension:" << _joystickSettings.enableManualControlPitchExtension()->rawValue().toBool();
609 qCDebug(JoystickLog) << " enableManualControlRollExtension:" << _joystickSettings.enableManualControlRollExtension()->rawValue().toBool();
610 qCDebug(JoystickLog) << " additionalAxesFunction:" << (_joystickSettings.additionalAxesFunction()->rawValue().toUInt() == 1 ? "RC_CHANNELS_OVERRIDE" : "MANUAL_CONTROL");
611 qCDebug(JoystickLog) << " enableAdditionalAxis1:" << _joystickSettings.enableAdditionalAxis1()->rawValue().toBool();
612 qCDebug(JoystickLog) << " enableAdditionalAxis2:" << _joystickSettings.enableAdditionalAxis2()->rawValue().toBool();
613 qCDebug(JoystickLog) << " enableAdditionalAxis3:" << _joystickSettings.enableAdditionalAxis3()->rawValue().toBool();
614 qCDebug(JoystickLog) << " enableAdditionalAxis4:" << _joystickSettings.enableAdditionalAxis4()->rawValue().toBool();
615 qCDebug(JoystickLog) << " enableAdditionalAxis5:" << _joystickSettings.enableAdditionalAxis5()->rawValue().toBool();
616 qCDebug(JoystickLog) << " enableAdditionalAxis6:" << _joystickSettings.enableAdditionalAxis6()->rawValue().toBool();
617 qCDebug(JoystickLog) << " transmitterMode:" << transmitterMode;
618
619 _clearAxisSettings();
620 if (calibrated) {
621 _saveAxisSettings(transmitterMode);
622 }
623
624 _clearButtonSettings();
625 _saveButtonSettings();
626}
627
628void Joystick::_remapFunctionsInFunctionMapToNewTransmittedMode(int fromMode, int toMode)
629{
630 static constexpr const int modeCount = 4;
631 static constexpr const int attitudeControlCount = 4;
632 static constexpr const AxisFunction_t mapping[modeCount][attitudeControlCount] = {
637 };
638
639 // First make a direct copy so the extension stick function are set correctly
640 AxisFunctionMap_t tempMap = _axisFunctionToJoystickAxisMap;
641
642 for (int i=0; i<attitudeControlCount; i++) {
643 auto fromAxisFunction = mapping[fromMode - 1][i];
644 auto toAxisFunction = mapping[toMode - 1][i];
645
646 tempMap[toAxisFunction] = _axisFunctionToJoystickAxisMap[fromAxisFunction];
647 }
648
649 for (int i = 0; i < maxAxisFunction; i++) {
650 auto axisFunction = static_cast<AxisFunction_t>(i);
651 _axisFunctionToJoystickAxisMap[axisFunction] = tempMap[axisFunction];
652 }
653}
654
655void Joystick::run()
656{
657 bool openFailed = false;
658 bool updateFailed = false;
659
660 if (!_open()) {
661 qCWarning(JoystickLog) << "Failed to open joystick:" << _name;
662 openFailed = true;
663 }
664
665 if (!openFailed) {
666 _axisElapsedTimer.start();
667
668 for (int buttonIndex = 0; buttonIndex < _totalButtonCount; buttonIndex++) {
669 if (_assignedButtonActions[buttonIndex]) {
670 _assignedButtonActions[buttonIndex]->buttonElapsedTimer.start();
671 }
672 }
673
674 while (!_exitPollingThread) {
675 if (!_update()) {
676 qCWarning(JoystickLog) << "Joystick disconnected or update failed:" << _name;
677 updateFailed = true;
678 break;
679 }
680
681 _handleButtons();
682
683 if (axisCount() != 0) {
684 _handleAxis();
685 }
686
687 const double axisFrequencyHz = _joystickSettings.axisFrequencyHz()->rawValue().toDouble();
688 const double buttonFrequencyHz = _joystickSettings.buttonFrequencyHz()->rawValue().toDouble();
689
690 const int sleep = qMin(static_cast<int>(1000.0 / axisFrequencyHz), static_cast<int>(1000.0 / buttonFrequencyHz)) / 2;
691 QThread::msleep(sleep);
692 }
693
694 _close();
695 }
696
697 if ((openFailed || updateFailed) && !_exitPollingThread) {
698 qCDebug(JoystickLog) << "Triggering joystick rescan after failure";
699 QMetaObject::invokeMethod(JoystickManager::instance(), "_checkForAddedOrRemovedJoysticks", Qt::QueuedConnection);
700 }
701}
702
703void Joystick::_updateButtonEventState(int buttonIndex, const bool buttonPressed, ButtonEvent_t &buttonEventState)
704{
705 if (buttonPressed) {
706 if (buttonEventState == ButtonEventNone) {
707 qCDebug(JoystickLog) << "Button" << buttonIndex << "down transition";
708 buttonEventState = ButtonEventDownTransition;
709 } else if (buttonEventState == ButtonEventDownTransition) {
710 qCDebug(JoystickLog) << "Button" << buttonIndex << "repeat";
711 buttonEventState = ButtonEventRepeat;
712 }
713 } else {
714 if (buttonEventState == ButtonEventDownTransition || buttonEventState == ButtonEventRepeat) {
715 qCDebug(JoystickLog) << "Button" << buttonIndex << "up transition";
716 buttonEventState = ButtonEventUpTransition;
717 } else if (buttonEventState == ButtonEventUpTransition) {
718 qCDebug(JoystickLog) << "Button" << buttonIndex << "none";
719 buttonEventState = ButtonEventNone;
720 }
721 }
722}
723
724void Joystick::_updateButtonEventStates(QVector<ButtonEvent_t> &buttonEventStates)
725{
726 if (buttonEventStates.size() < _totalButtonCount) {
727 qCWarning(JoystickLog) << "Internal Error: buttonEventStates size incorrect!";
728 return;
729 }
730
731 // Update standard buttons - index 0 to buttonCount-1
732 for (int buttonIndex = 0; buttonIndex < _buttonCount; buttonIndex++) {
733 const bool buttonIsPressed = _getButton(buttonIndex);
734 _updateButtonEventState(buttonIndex, buttonIsPressed, buttonEventStates[buttonIndex]);
735 }
736
737 // Update hat buttons - indexes buttonCount to totalButtonCount-1
738 const int numHatButtons = 4;
739 int nextIndex = _buttonCount;
740 for (int hatIndex = 0; hatIndex < _hatCount; hatIndex++) {
741 for (int hatButtonIndex = 0; hatButtonIndex < numHatButtons; hatButtonIndex++) {
742 const bool buttonIsPressed = _getHat(hatIndex, hatButtonIndex);
743 const int currentIndex = nextIndex;
744 _updateButtonEventState(currentIndex, buttonIsPressed, buttonEventStates[currentIndex]);
745 ++nextIndex;
746 }
747 }
748}
749
750void Joystick::_handleButtons()
751{
752 if (_pollingFlags == PollingNone) {
753 qCWarning(JoystickLog) << "Internal Error: Joystick not polling!";
754 return;
755 }
756
757 _updateButtonEventStates(_buttonEventStates);
758
759 if (_pollingFlags.testFlag(PollingForConfiguration)) {
760 for (int buttonIndex = 0; buttonIndex < _totalButtonCount; buttonIndex++) {
761 if (_buttonEventStates[buttonIndex] == ButtonEventDownTransition) {
762 qCDebug(JoystickLog) << "Button pressed - button" << buttonIndex;
763 emit rawButtonPressedChanged(buttonIndex, true);
764 } else if (_buttonEventStates[buttonIndex] == ButtonEventUpTransition) {
765 qCDebug(JoystickLog) << "Button released - button" << buttonIndex;
766 emit rawButtonPressedChanged(buttonIndex, false);
767 }
768 }
769 } else if (_pollingFlags.testFlag(PollingForVehicle)) {
770 Vehicle *const vehicle = _pollingVehicle;
771 if (!vehicle) {
772 qCWarning(JoystickLog) << "Internal Error: No vehicle for joystick!";
773 return;
774 }
775 if (!_joystickManager->activeJoystickEnabledForActiveVehicle()) {
776 qCWarning(JoystickLog) << "Internal Error: Joystick not enabled for vehicle!";
777 return;
778 }
779 if (!_joystickSettings.calibrated()->rawValue().toBool()) {
780 return;
781 }
782
783 //-- Process button press/release
784 const int buttonDelay = static_cast<int>(1000.0 / _joystickSettings.buttonFrequencyHz()->rawValue().toDouble());
785 QSet<QString> executedActions;
786 for (int buttonIndex = 0; buttonIndex < _totalButtonCount; buttonIndex++) {
787 if (!_assignedButtonActions[buttonIndex]) {
788 continue;
789 }
790 auto assignedAction = _assignedButtonActions[buttonIndex];
791
792 const QString buttonAction = assignedAction->actionName;
793 if (buttonAction.isEmpty() || (buttonAction == _buttonActionNone)) {
794 continue;
795 }
796
797 auto buttonEventState = _buttonEventStates[buttonIndex];
798 if (buttonEventState == ButtonEventDownTransition || buttonEventState == ButtonEventRepeat) {
799 if (assignedAction->repeat) {
800 if (assignedAction->buttonElapsedTimer.elapsed() > buttonDelay) {
801 assignedAction->buttonElapsedTimer.start();
802 qCDebug(JoystickLog) << "Repeat - button:action" << buttonIndex << buttonAction;
803 // Post to the GUI thread for safe access to class members.
804 QMetaObject::invokeMethod(this, [this, buttonAction]() {
805 _executeButtonAction(buttonAction, ButtonEventRepeat);
806 }, Qt::QueuedConnection);
807 }
808 } else {
809 if (buttonEventState == ButtonEventDownTransition) {
810 // Check for multi-button action
811 QList<int> multiActionButtons = { buttonIndex };
812 bool allActionButtonsPressed = true;
813 for (int multiIndex = 0; multiIndex < _totalButtonCount; multiIndex++) {
814 if (multiIndex == buttonIndex) {
815 continue;
816 }
817 if (_assignedButtonActions[multiIndex] && (_assignedButtonActions[multiIndex]->actionName == buttonAction)) {
818 // We found a multi-button action
819 if (_buttonEventStates[multiIndex] == ButtonEventDownTransition || _buttonEventStates[multiIndex] == ButtonEventRepeat) {
820 // So far so good
821 multiActionButtons.append(multiIndex);
822 } else {
823 // We are missing a press we need, skip this multi-button action only
824 allActionButtonsPressed = false;
825 break;
826 }
827 }
828 }
829
830 if (!allActionButtonsPressed) {
831 continue;
832 }
833
834 if (multiActionButtons.size() > 1) {
835 qCDebug(JoystickLog) << "Multi-button action - buttons:action" << multiActionButtons << buttonAction;
836 } else {
837 qCDebug(JoystickLog) << "Action triggered - button:Action" << buttonIndex << buttonAction;
838 }
839 // Multiple buttons can share the same action name (multi-button feature).
840 // Guard against executing the action more than once per poll cycle when
841 // several such buttons are all in the same event state simultaneously.
842 if (!executedActions.contains(buttonAction)) {
843 // Post to the GUI thread for safe access to class members.
844 QMetaObject::invokeMethod(this, [this, buttonAction]() {
845 _executeButtonAction(buttonAction, ButtonEventDownTransition);
846 }, Qt::QueuedConnection);
847 executedActions.insert(buttonAction);
848 }
849 continue;
850 }
851 }
852 } else if (buttonEventState == ButtonEventUpTransition) {
853 // Same deduplication guard for release events.
854 if (!executedActions.contains(buttonAction)) {
855 // Post to the GUI thread for safe access to class members.
856 QMetaObject::invokeMethod(this, [this, buttonAction]() {
857 _executeButtonAction(buttonAction, ButtonEventUpTransition);
858 }, Qt::QueuedConnection);
859 executedActions.insert(buttonAction);
860 }
861 continue;
862 }
863 }
864 }
865}
866
867float Joystick::_adjustRange(int value, const AxisCalibration_t &calibration, bool withDeadbands)
868{
869 float valueNormalized;
870 float axisLength;
871 float axisBasis;
872
873 if (calibration.center == calibration.min) {
874 axisBasis = 1.0f;
875 valueNormalized = static_cast<float>(std::max(0, value - calibration.center));
876 axisLength = calibration.max - calibration.center;
877 } else if (calibration.center == calibration.max) {
878 axisBasis = -1.0f;
879 valueNormalized = static_cast<float>(std::max(0, calibration.center - value));
880 axisLength = calibration.center - calibration.min;
881 } else if (value > calibration.center) {
882 axisBasis = 1.0f;
883 valueNormalized = value - calibration.center;
884 axisLength = calibration.max - calibration.center;
885 } else {
886 axisBasis = -1.0f;
887 valueNormalized = calibration.center - value;
888 axisLength = calibration.center - calibration.min;
889 }
890
891 if (axisLength <= 0.0f) {
892 return 0.0f;
893 }
894
895 float axisPercent;
896 if (withDeadbands) {
897 if (valueNormalized > calibration.deadband) {
898 axisPercent = (valueNormalized - calibration.deadband) / (axisLength - calibration.deadband);
899 } else if (valueNormalized<-calibration.deadband) {
900 axisPercent = (valueNormalized + calibration.deadband) / (axisLength - calibration.deadband);
901 } else {
902 axisPercent = 0.f;
903 }
904 } else {
905 axisPercent = valueNormalized / axisLength;
906 }
907
908 float correctedValue = axisBasis * axisPercent;
909 if (calibration.reversed) {
910 correctedValue *= -1.0f;
911 }
912
913 return std::max(-1.0f, std::min(correctedValue, 1.0f));
914}
915
916uint16_t Joystick::_adjustRangeToRcOverridePwm(int value, const AxisCalibration_t &calibration, bool withDeadbands)
917{
918 const float normalizedValue = _adjustRange(value, calibration, withDeadbands);
919 const bool oneSidedAxis = (calibration.center == calibration.min) || (calibration.center == calibration.max);
920
921 float pwmValue;
922 if (oneSidedAxis) {
923 pwmValue = 1000.0f + (std::clamp(normalizedValue, 0.0f, 1.0f) * 1000.0f);
924 } else {
925 pwmValue = 1500.0f + (std::clamp(normalizedValue, -1.0f, 1.0f) * 500.0f);
926 }
927
928 return static_cast<uint16_t>(std::lround(std::clamp(pwmValue, 1000.0f, 2000.0f)));
929}
930
931void Joystick::_handleAxis()
932{
933 const int axisDelay = static_cast<int>(1000.0 / _joystickSettings.axisFrequencyHz()->rawValue().toDouble());
934 if (_axisElapsedTimer.elapsed() <= axisDelay) {
935 return;
936 }
937
938 _axisElapsedTimer.start();
939
940 if (_pollingFlags == PollingNone) {
941 qCWarning(JoystickLog) << "Internal Error: Joystick not polling!";
942 return;
943 }
944
945 if (_pollingFlags.testFlag(PollingForConfiguration)) {
946 // Signal the axis values to Joystick Config/Cal. Axes in Joystick terminology are the same as Channels in
947 // RemoteControlCalibrationController terminology.
948 QVector<int> channelValues(_axisCount);
949 for (int axisIndex = 0; axisIndex < _axisCount; axisIndex++) {
950 channelValues[axisIndex] = _getAxisValue(axisIndex);
951 }
952 emit rawChannelValuesChanged(channelValues);
953 } else if (_pollingFlags.testFlag(PollingForVehicle)) {
954 Vehicle *const vehicle = _pollingVehicle;
955 if (!vehicle) {
956 qCWarning(JoystickLog) << "Internal Error: No vehicle for joystick!";
957 return;
958 }
959 if (!_joystickManager->activeJoystickEnabledForActiveVehicle()) {
960 qCWarning(JoystickLog) << "Internal Error: Joystick not enabled for vehicle!";
961 return;
962 }
963 if (!_joystickSettings.calibrated()->rawValue().toBool()) {
964 return;
965 }
966
967 bool useDeadband = _joystickSettings.useDeadband()->rawValue().toBool();
968 bool throttleModeCenterZero = _joystickSettings.throttleModeCenterZero()->rawValue().toBool();
969 bool negativeThrust = _joystickSettings.negativeThrust()->rawValue().toBool();
970 bool circleCorrection = _joystickSettings.circleCorrection()->rawValue().toBool();
971 bool throttleSmoothing = _joystickSettings.throttleSmoothing()->rawValue().toBool();
972 bool additionalAxesFunctionIsManualControl = _joystickSettings.additionalAxesFunction()->rawValue().toUInt() == 0;
973 double exponentialPercent = _joystickSettings.exponentialPct()->rawValue().toDouble();
974
975 if (_getJoystickAxisForAxisFunction(rollFunction) == kJoystickAxisNotAssigned ||
976 _getJoystickAxisForAxisFunction(pitchFunction) == kJoystickAxisNotAssigned ||
977 _getJoystickAxisForAxisFunction(yawFunction) == kJoystickAxisNotAssigned ||
978 _getJoystickAxisForAxisFunction(throttleFunction) == kJoystickAxisNotAssigned) {
979 qCWarning(JoystickLog) << "Internal Error: Missing attitude control axis function mapping!";
980 return;
981 }
982 int axisIndex = _getJoystickAxisForAxisFunction(rollFunction);
983 float roll = _adjustRange(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband);
984 axisIndex = _getJoystickAxisForAxisFunction(pitchFunction);
985 float pitch = _adjustRange(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband);
986 axisIndex = _getJoystickAxisForAxisFunction(yawFunction);
987 float yaw = _adjustRange(_getAxisValue(axisIndex), _rgCalibration[axisIndex],useDeadband);
988 axisIndex = _getJoystickAxisForAxisFunction(throttleFunction);
989 float throttle = _adjustRange(_getAxisValue(axisIndex), _rgCalibration[axisIndex], throttleModeCenterZero ? useDeadband : false);
990
991 float pitchExtension = qQNaN();
992 if (_joystickSettings.enableManualControlPitchExtension()->rawValue().toBool()) {
993 if (_getJoystickAxisForAxisFunction(pitchExtensionFunction) == kJoystickAxisNotAssigned) {
994 qCWarning(JoystickLog) << "Internal Error: Missing pitch extension axis function mapping!";
995 return;
996 }
997 axisIndex = _getJoystickAxisForAxisFunction(pitchExtensionFunction);
998 pitchExtension = _adjustRange(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband);
999 }
1000 float rollExtension = qQNaN();
1001 if (_joystickSettings.enableManualControlRollExtension()->rawValue().toBool()) {
1002 if (_getJoystickAxisForAxisFunction(rollExtensionFunction) == kJoystickAxisNotAssigned) {
1003 qCWarning(JoystickLog) << "Internal Error: Missing roll extension axis function mapping!";
1004 return;
1005 }
1006 axisIndex = _getJoystickAxisForAxisFunction(rollExtensionFunction);
1007 rollExtension = _adjustRange(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband);
1008 }
1009 std::array<uint16_t, 6> auxRcOverridePwm{};
1010 std::array<bool, 6> auxRcOverrideEnabled{};
1011
1012 float auxManualControl1 = qQNaN();
1013 if (_joystickSettings.enableAdditionalAxis1()->rawValue().toBool()) {
1014 if (_getJoystickAxisForAxisFunction(additionalAxis1Function) == kJoystickAxisNotAssigned) {
1015 qCWarning(JoystickLog) << "Internal Error: Missing additional axis 1 function mapping!";
1016 return;
1017 }
1018 axisIndex = _getJoystickAxisForAxisFunction(additionalAxis1Function);
1019 if (additionalAxesFunctionIsManualControl) {
1020 auxManualControl1 = _adjustRange(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband);
1021 } else {
1022 auxRcOverridePwm[0] = _adjustRangeToRcOverridePwm(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband);
1023 auxRcOverrideEnabled[0] = true;
1024 }
1025 }
1026 float auxManualControl2 = qQNaN();
1027 if (_joystickSettings.enableAdditionalAxis2()->rawValue().toBool()) {
1028 if (_getJoystickAxisForAxisFunction(additionalAxis2Function) == kJoystickAxisNotAssigned) {
1029 qCWarning(JoystickLog) << "Internal Error: Missing additional axis 2 function mapping!";
1030 return;
1031 }
1032 axisIndex = _getJoystickAxisForAxisFunction(additionalAxis2Function);
1033 if (additionalAxesFunctionIsManualControl) {
1034 auxManualControl2 = _adjustRange(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband);
1035 } else {
1036 auxRcOverridePwm[1] = _adjustRangeToRcOverridePwm(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband);
1037 auxRcOverrideEnabled[1] = true;
1038 }
1039 }
1040 float auxManualControl3 = qQNaN();
1041 if (_joystickSettings.enableAdditionalAxis3()->rawValue().toBool()) {
1042 if (_getJoystickAxisForAxisFunction(additionalAxis3Function) == kJoystickAxisNotAssigned) {
1043 qCWarning(JoystickLog) << "Internal Error: Missing additional axis 3 function mapping!";
1044 return;
1045 }
1046 axisIndex = _getJoystickAxisForAxisFunction(additionalAxis3Function);
1047 if (additionalAxesFunctionIsManualControl) {
1048 auxManualControl3 = _adjustRange(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband);
1049 } else {
1050 auxRcOverridePwm[2] = _adjustRangeToRcOverridePwm(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband);
1051 auxRcOverrideEnabled[2] = true;
1052 }
1053 }
1054 float auxManualControl4 = qQNaN();
1055 if (_joystickSettings.enableAdditionalAxis4()->rawValue().toBool()) {
1056 if (_getJoystickAxisForAxisFunction(additionalAxis4Function) == kJoystickAxisNotAssigned) {
1057 qCWarning(JoystickLog) << "Internal Error: Missing additional axis 4 function mapping!";
1058 return;
1059 }
1060 axisIndex = _getJoystickAxisForAxisFunction(additionalAxis4Function);
1061 if (additionalAxesFunctionIsManualControl) {
1062 auxManualControl4 = _adjustRange(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband);
1063 } else {
1064 auxRcOverridePwm[3] = _adjustRangeToRcOverridePwm(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband);
1065 auxRcOverrideEnabled[3] = true;
1066 }
1067 }
1068 float auxManualControl5 = qQNaN();
1069 if (_joystickSettings.enableAdditionalAxis5()->rawValue().toBool()) {
1070 if (_getJoystickAxisForAxisFunction(additionalAxis5Function) == kJoystickAxisNotAssigned) {
1071 qCWarning(JoystickLog) << "Internal Error: Missing additional axis 5 function mapping!";
1072 return;
1073 }
1074 axisIndex = _getJoystickAxisForAxisFunction(additionalAxis5Function);
1075 if (additionalAxesFunctionIsManualControl) {
1076 auxManualControl5 = _adjustRange(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband);
1077 } else {
1078 auxRcOverridePwm[4] = _adjustRangeToRcOverridePwm(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband);
1079 auxRcOverrideEnabled[4] = true;
1080 }
1081 }
1082 float auxManualControl6 = qQNaN();
1083 if (_joystickSettings.enableAdditionalAxis6()->rawValue().toBool()) {
1084 if (_getJoystickAxisForAxisFunction(additionalAxis6Function) == kJoystickAxisNotAssigned) {
1085 qCWarning(JoystickLog) << "Internal Error: Missing additional axis 6 function mapping!";
1086 return;
1087 }
1088 axisIndex = _getJoystickAxisForAxisFunction(additionalAxis6Function);
1089 if (additionalAxesFunctionIsManualControl) {
1090 auxManualControl6 = _adjustRange(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband);
1091 } else {
1092 auxRcOverridePwm[5] = _adjustRangeToRcOverridePwm(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband);
1093 auxRcOverrideEnabled[5] = true;
1094 }
1095 }
1096
1097 if (throttleSmoothing) {
1098 static float throttleSmoothingValue = 0.f;
1099 throttleSmoothingValue += (throttle * (40 / 1000.f)); // for throttle to change from min to max it will take 1000ms (40ms is a loop time)
1100 throttleSmoothingValue = std::max(static_cast<float>(-1.f), std::min(throttleSmoothingValue, static_cast<float>(1.f)));
1101 throttle = throttleSmoothingValue;
1102 }
1103
1104 if (circleCorrection) {
1105 const float roll_limited = std::max(static_cast<float>(-M_PI_4), std::min(roll, static_cast<float>(M_PI_4)));
1106 const float pitch_limited = std::max(static_cast<float>(-M_PI_4), std::min(pitch, static_cast<float>(M_PI_4)));
1107 const float yaw_limited = std::max(static_cast<float>(-M_PI_4), std::min(yaw, static_cast<float>(M_PI_4)));
1108 const float throttle_limited = std::max(static_cast<float>(-M_PI_4), std::min(throttle, static_cast<float>(M_PI_4)));
1109
1110 // Map from unit circle to linear range and limit
1111 roll = std::max(-1.0f, std::min(tanf(asinf(roll_limited)), 1.0f));
1112 pitch = std::max(-1.0f, std::min(tanf(asinf(pitch_limited)), 1.0f));
1113 yaw = std::max(-1.0f, std::min(tanf(asinf(yaw_limited)), 1.0f));
1114 throttle = std::max(-1.0f, std::min(tanf(asinf(throttle_limited)), 1.0f));
1115 }
1116
1117 if ( exponentialPercent > 0.0 ) {
1118 const float exponential = -static_cast<float>(exponentialPercent / 100.0);
1119 roll = -exponential * powf(roll, 3) + ((1 + exponential) * roll);
1120 pitch = -exponential * powf(pitch,3) + ((1 + exponential) * pitch);
1121 yaw = -exponential * powf(yaw, 3) + ((1 + exponential) * yaw);
1122 }
1123
1124 // Adjust throttle to 0:1 range
1125 if (throttleModeCenterZero && vehicle->supports()->throttleModeCenterZero()) {
1126 if (!vehicle->supports()->negativeThrust() || !negativeThrust) {
1127 throttle = std::max(0.0f, throttle);
1128 }
1129 } else {
1130 throttle = (throttle + 1.0f) / 2.0f;
1131 }
1132
1133 if (additionalAxesFunctionIsManualControl) {
1134 qCDebug(JoystickVerboseLog)
1135 << name()
1136 << "roll:" << roll
1137 << "pitch:" << -pitch
1138 << "yaw:" << yaw
1139 << "throttle:" << throttle
1140 << "pitchExtension:" << pitchExtension
1141 << "rollExtension:" << rollExtension
1142 << "additionalAxesFunction: MANUAL_CONTROL"
1143 << "aux1:" << auxManualControl1
1144 << "aux2:" << auxManualControl2
1145 << "aux3:" << auxManualControl3
1146 << "aux4:" << auxManualControl4
1147 << "aux5:" << auxManualControl5
1148 << "aux6:" << auxManualControl6;
1149 } else {
1150 qCDebug(JoystickVerboseLog)
1151 << name()
1152 << "roll:" << roll
1153 << "pitch:" << -pitch
1154 << "yaw:" << yaw
1155 << "throttle:" << throttle
1156 << "pitchExtension:" << pitchExtension
1157 << "rollExtension:" << rollExtension
1158 << "additionalAxesFunction: RC_CHANNELS_OVERRIDE"
1159 << "rcOverridePwm[0]:" << auxRcOverridePwm[0] << "enabled:" << auxRcOverrideEnabled[0]
1160 << "rcOverridePwm[1]:" << auxRcOverridePwm[1] << "enabled:" << auxRcOverrideEnabled[1]
1161 << "rcOverridePwm[2]:" << auxRcOverridePwm[2] << "enabled:" << auxRcOverrideEnabled[2]
1162 << "rcOverridePwm[3]:" << auxRcOverridePwm[3] << "enabled:" << auxRcOverrideEnabled[3]
1163 << "rcOverridePwm[4]:" << auxRcOverridePwm[4] << "enabled:" << auxRcOverrideEnabled[4]
1164 << "rcOverridePwm[5]:" << auxRcOverridePwm[5] << "enabled:" << auxRcOverrideEnabled[5];
1165 }
1166
1167 // NOTE: The buttonPressedBits going to MANUAL_CONTROL are currently used by ArduSub (and it only handles 16 bits)
1168 // Set up button bitmap
1169 quint64 buttonPressedBits = 0;
1170 for (int buttonIndex = 0; buttonIndex < _totalButtonCount; buttonIndex++) {
1171 const quint64 buttonBit = static_cast<quint64>(1LL << buttonIndex);
1172 if (_buttonEventStates[buttonIndex] == ButtonEventDownTransition || _buttonEventStates[buttonIndex] == ButtonEventRepeat) {
1173 buttonPressedBits |= buttonBit;
1174 }
1175 }
1176
1177 emit axisValues(roll, pitch, yaw, throttle);
1178
1179 const uint16_t lowButtons = static_cast<uint16_t>(buttonPressedBits & 0xFFFF);
1180 const uint16_t highButtons = static_cast<uint16_t>((buttonPressedBits >> 16) & 0xFFFF);
1181
1182
1183 vehicle->sendJoystickDataThreadSafe(roll, pitch, yaw, throttle, lowButtons, highButtons, pitchExtension, rollExtension, auxManualControl1, auxManualControl2, auxManualControl3, auxManualControl4, auxManualControl5, auxManualControl6);
1184 vehicle->sendJoystickAuxRcOverrideThreadSafe(auxRcOverridePwm, auxRcOverrideEnabled, !additionalAxesFunctionIsManualControl);
1185 }
1186}
1187
1188void Joystick::_startPollingForActiveVehicle()
1189{
1191 if (!activeVehicle) {
1192 qCWarning(JoystickLog) << "Internal Error: No active vehicle to poll for";
1193 return;
1194 }
1195 _startPollingForVehicle(*activeVehicle);
1196}
1197
1198void Joystick::_startPollingForVehicle(Vehicle &vehicle)
1199{
1200 qCDebug(JoystickLog) << "Starting joystick polling for vehicle. Vehicle id:" << vehicle.id() << "Current flags:" << _pollingFlagsToString(_pollingFlags);
1201
1202 if (_pollingFlags.testFlag(PollingForVehicle)) {
1203 qCWarning(JoystickLog) << "Internal Error: Joystick already polling for vehicle!";
1204 return;
1205 }
1206
1207 _pollingVehicle = &vehicle;
1208 qCDebug(JoystickLog) << "Started joystick polling for vehicle. Vehicle id:" << _pollingVehicle->id();
1209
1210 _buildAvailableButtonsActionList(_pollingVehicle);
1211
1212 (void) connect(this, &Joystick::setArmed, _pollingVehicle, &Vehicle::setArmedShowError);
1213 (void) connect(this, &Joystick::setVtolInFwdFlight, _pollingVehicle, &Vehicle::setVtolInFwdFlight);
1214 (void) connect(this, &Joystick::setFlightMode, _pollingVehicle, &Vehicle::setFlightMode);
1215 (void) connect(this, &Joystick::emergencyStop, _pollingVehicle, &Vehicle::emergencyStop);
1216 (void) connect(this, &Joystick::gripperAction, _pollingVehicle, &Vehicle::sendGripperAction);
1217 (void) connect(this, &Joystick::landingGearDeploy, _pollingVehicle, &Vehicle::landingGearDeploy);
1218 (void) connect(this, &Joystick::landingGearRetract, _pollingVehicle, &Vehicle::landingGearRetract);
1219 (void) connect(this, &Joystick::motorInterlock, _pollingVehicle, &Vehicle::motorInterlock);
1220
1221 (void) connect(_pollingVehicle, &Vehicle::flightModesChanged, this, &Joystick::_flightModesChanged);
1222
1223 if (GimbalController *const gimbal = _pollingVehicle->gimbalController()) {
1224 (void) connect(this, &Joystick::gimbalYawLock, gimbal, &GimbalController::gimbalYawLock);
1225 (void) connect(this, &Joystick::centerGimbal, gimbal, &GimbalController::centerGimbal);
1226 (void) connect(this, &Joystick::gimbalPitchStart, gimbal, &GimbalController::gimbalPitchStart);
1227 (void) connect(this, &Joystick::gimbalYawStart, gimbal, &GimbalController::gimbalYawStart);
1228 (void) connect(this, &Joystick::gimbalPitchStop, gimbal, &GimbalController::gimbalPitchStop);
1229 (void) connect(this, &Joystick::gimbalYawStop, gimbal, &GimbalController::gimbalYawStop);
1230 }
1231
1232 _pollingFlags |= PollingForVehicle;
1233 _startPollingThread();
1234}
1235
1236void Joystick::_startPollingForConfiguration()
1237{
1238 qCDebug(JoystickLog) << "Starting joystick polling for configuration. Current flags:" << _pollingFlagsToString(_pollingFlags);
1239
1240 if (_pollingFlags.testFlag(PollingForConfiguration)) {
1241 qCWarning(JoystickLog) << "Internal Error: Joystick already polling for configuration!";
1242 return;
1243 }
1244
1245 _pollingFlags |= PollingForConfiguration;
1246 _startPollingThread();
1247}
1248
1249void Joystick::_stopPollingForConfiguration()
1250{
1251 qCDebug(JoystickLog) << "Stopping joystick polling for configuration. Current flags:" << _pollingFlagsToString(_pollingFlags);
1252
1253 if (!_pollingFlags.testFlag(PollingForConfiguration)) {
1254 qCWarning(JoystickLog) << "Internal Error: Joystick not polling for configuration!";
1255 return;
1256 }
1257
1258 if (!isRunning()) {
1259 qCWarning(JoystickLog) << "Internal Error: Joystick polling thread not running!";
1260 }
1261
1262 const PollingFlags remainingFlags = _pollingFlags & ~PollingFlags(PollingForConfiguration);
1263
1264 // Stop the thread BEFORE updating _pollingFlags. If we cleared the flags first and the
1265 // thread was still running, _handleButtons()/_handleAxis() would see PollingNone and
1266 // fire a spurious "Internal Error: Joystick not polling!" warning.
1267 if (remainingFlags == PollingNone) {
1268 _stopPollingThread();
1269 }
1270
1271 _pollingFlags = remainingFlags;
1272 qCDebug(JoystickLog) << "Remaining flags:" << _pollingFlagsToString(_pollingFlags);
1273
1274 if (remainingFlags.testFlag(PollingForVehicle) && !isRunning()) {
1275 qCWarning(JoystickLog) << "Internal Error: Joystick polling not running! Forcing start of polling thread. Continuing polling for vehicle.";
1276 _startPollingThread();
1277 }
1278}
1279
1280void Joystick::_stopAllPollingForVehicle()
1281{
1282 qCDebug(JoystickLog) << "Stopping all joystick polling for vehicle. Current flags:" << _pollingFlagsToString(_pollingFlags);
1283
1284 if (_pollingVehicle) {
1285 _pollingVehicle->sendJoystickAuxRcOverrideThreadSafe({}, {}, false);
1286 (void) disconnect(this, nullptr, _pollingVehicle, nullptr);
1287 (void) disconnect(_pollingVehicle, &Vehicle::flightModesChanged, this, &Joystick::_flightModesChanged);
1288 if (GimbalController *const gimbal = _pollingVehicle->gimbalController()) {
1289 (void) disconnect(this, nullptr, gimbal, nullptr);
1290 }
1291 if (!isRunning()) {
1292 qCWarning(JoystickLog) << "Joystick polling thread not running even though _pollingVehicle was set.";
1293 }
1294 }
1295
1296 const PollingFlags remainingFlags = _pollingFlags & ~PollingFlags(PollingForVehicle);
1297
1298 // Stop the thread BEFORE updating _pollingFlags. If we cleared the flags first and the
1299 // thread was still running, _handleButtons()/_handleAxis() would see PollingNone and
1300 // fire a spurious "Internal Error: Joystick not polling!" warning.
1301 if (remainingFlags == PollingNone) {
1302 _stopPollingThread();
1303 }
1304
1305 // Clear _pollingVehicle AFTER updating _pollingFlags so the polling thread never sees
1306 // PollingForVehicle set with a null _pollingVehicle, which would fire spurious
1307 // "Internal Error: No vehicle for joystick!" warnings.
1308 _pollingVehicle = nullptr;
1309 _pollingFlags = remainingFlags;
1310 qCDebug(JoystickLog) << "Remaining flags:" << _pollingFlagsToString(_pollingFlags);
1311
1312 if (remainingFlags.testFlag(PollingForConfiguration) && !isRunning()) {
1313 qCWarning(JoystickLog) << "Joystick polling thread not running but configuration polling flag set. Forcing start.";
1314 _startPollingThread();
1315 }
1316}
1317
1318void Joystick::_startPollingThread()
1319{
1320 if (isRunning()) {
1321 qCDebug(JoystickLog) << "Polling thread already running. Flags:" << _pollingFlagsToString(_pollingFlags);
1322 } else {
1323 qCDebug(JoystickLog) << "Starting polling thread. Flags:" << _pollingFlagsToString(_pollingFlags);
1324 _exitPollingThread = false;
1325 start();
1326 }
1327}
1328
1329void Joystick::_stopPollingThread()
1330{
1331 if (isRunning()) {
1332 qCDebug(JoystickLog) << "Stopping polling thread. Flags:" << _pollingFlagsToString(_pollingFlags);
1333 _exitPollingThread = true;
1334 if (QThread::currentThread() == this) {
1335 qCWarning(JoystickLog) << "Skipping wait() on joystick thread to avoid deadlock";
1336 } else {
1337 wait();
1338 }
1339 // _exitPollingThread is reset to false in _startPollingThread() before the next start()
1340 } else {
1341 qCDebug(JoystickLog) << "Polling thread already stopped. Flags:" << _pollingFlagsToString(_pollingFlags);
1342 }
1343}
1344
1345QString Joystick::_pollingFlagsToString(PollingFlags flags) const
1346{
1347 if (flags == PollingNone) {
1348 return QStringLiteral("None");
1349 }
1350 QStringList parts;
1351 if (flags.testFlag(PollingForVehicle)) {
1352 parts << QStringLiteral("PollingForVehicle");
1353 }
1354 if (flags.testFlag(PollingForConfiguration)) {
1355 parts << QStringLiteral("PollingForConfiguration");
1356 }
1357 return parts.join(QStringLiteral("|"));
1358}
1359
1360void Joystick::setAxisCalibration(int axis, const AxisCalibration_t &calibration)
1361{
1362 if (!_validAxis(axis)) {
1363 return;
1364 }
1365
1366 _rgCalibration[axis] = calibration;
1367}
1368
1370{
1371 if (!_validAxis(axis)) {
1372 return AxisCalibration_t{};
1373 }
1374
1375 return _rgCalibration[axis];
1376}
1377
1378void Joystick::_setJoystickAxisForAxisFunction(AxisFunction_t axisFunction, int joystickAxis)
1379{
1380 if (axisFunction == maxAxisFunction) {
1381 qCWarning(JoystickLog) << "Internal Error: maxAxisFunction passed to _setJoystickAxisForAxisFunction";
1382 return;
1383 }
1384 if (joystickAxis == kJoystickAxisNotAssigned) {
1385 qCWarning(JoystickLog) << "Internal Error: kJoystickAxisNotAssigned passed to _setJoystickAxisForAxisFunction";
1386 return;
1387 }
1388
1389 if (!_validAxis(joystickAxis)) {
1390 return;
1391 }
1392
1393 _axisFunctionToJoystickAxisMap[axisFunction] = joystickAxis;
1394}
1395
1396int Joystick::_getJoystickAxisForAxisFunction(AxisFunction_t axisFunction) const
1397{
1398 if (axisFunction == maxAxisFunction) {
1399 qCWarning(JoystickLog) << "Internal Error: maxAxisFunction passed to _getJoystickAxisForAxisFunction";
1400 return kJoystickAxisNotAssigned;
1401 }
1402
1403 return _axisFunctionToJoystickAxisMap.value(axisFunction, kJoystickAxisNotAssigned);
1404}
1405
1407{
1408 switch (axisFunction) {
1409 case rollFunction:
1411 case pitchFunction:
1413 case yawFunction:
1415 case throttleFunction:
1433 case maxAxisFunction:
1435 }
1436 Q_UNREACHABLE();
1437}
1438
1440{
1441 switch (stickFunction) {
1443 return rollFunction;
1445 return pitchFunction;
1447 return yawFunction;
1449 return throttleFunction;
1465 return rollExtensionFunction;
1467 return maxAxisFunction;
1468 }
1469 Q_UNREACHABLE();
1470}
1471
1473{
1474 _setJoystickAxisForAxisFunction(mapRCCStickFunctionToAxisFunction(stickFunction), channel);
1475}
1476
1478{
1479 return _getJoystickAxisForAxisFunction(mapRCCStickFunctionToAxisFunction(stickFunction));
1480}
1481
1482void Joystick::setButtonRepeat(int button, bool repeat)
1483{
1484 if (!_validButton(button) || !_assignedButtonActions[button]) {
1485 return;
1486 }
1487
1488 _assignedButtonActions[button]->repeat = repeat;
1489 _assignedButtonActions[button]->buttonElapsedTimer.start();
1490
1491 QSettings settings;
1492 settings.beginGroup(_joystickSettings.settingsGroup());
1493 settings.beginGroup(QString::fromLatin1(kButtonActionArrayGroup));
1494 settings.beginGroup(QString::number(button));
1495 const QString repeatKey = QString::fromLatin1(kButtonRepeatKey);
1496 settings.setValue(repeatKey, repeat);
1497 settings.endGroup();
1498 settings.endGroup();
1499 settings.endGroup();
1500}
1501
1503{
1504 if (!_validButton(button) || !_assignedButtonActions[button]) {
1505 return false;
1506 }
1507
1508 return _assignedButtonActions[button]->repeat;
1509}
1510
1511void Joystick::setButtonAction(int button, const QString& actionName)
1512{
1513 if (!_validButton(button)) {
1514 return;
1515 }
1516
1517 qCDebug(JoystickLog) << "button:actionName" << button << actionName;
1518
1519 QSettings settings;
1520 settings.beginGroup(_joystickSettings.settingsGroup());
1521 settings.beginGroup(QString::fromLatin1(kButtonActionArrayGroup));
1522 settings.beginGroup(QString::number(button));
1523 const QString actionNameKey = QString::fromLatin1(kButtonActionNameKey);
1524 const QString repeatKey = QString::fromLatin1(kButtonRepeatKey);
1525
1526 if (actionName.isEmpty() || actionName == _buttonActionNone) {
1527 if (_assignedButtonActions[button]) {
1528 delete _assignedButtonActions[button];
1529 _assignedButtonActions[button] = nullptr;
1530 }
1531 settings.setValue(actionNameKey, _buttonActionNone);
1532 settings.setValue(repeatKey, false);
1533 } else {
1534 if (!_assignedButtonActions[button]) {
1535 _assignedButtonActions[button] = new AssignedButtonAction(actionName, false /* repeat */);
1536 } else {
1537 _assignedButtonActions[button]->actionName = actionName;
1538 //-- Make sure repeat is off if this action doesn't support repeats
1539 const int idx = _findAvailableButtonActionIndex(actionName);
1540 if (idx >= 0) {
1541 const AvailableButtonAction *const buttonAction = qobject_cast<const AvailableButtonAction*>(_availableButtonActions->get(idx));
1542 if (!buttonAction->canRepeat()) {
1543 _assignedButtonActions[button]->repeat = false;
1544 }
1545 }
1546 }
1547
1548 settings.setValue(actionNameKey, _assignedButtonActions[button]->actionName);
1549 settings.setValue(repeatKey, _assignedButtonActions[button]->repeat);
1550 }
1551
1552 settings.endGroup();
1553 settings.endGroup();
1554 settings.endGroup();
1555
1556 emit buttonActionsChanged();
1557}
1558
1559QString Joystick::getButtonAction(int button) const
1560{
1561 if (_validButton(button)) {
1562 if (_assignedButtonActions[button]) {
1563 return _assignedButtonActions[button]->actionName;
1564 }
1565 }
1566
1567 return QString(_buttonActionNone);
1568}
1569
1570QStringList Joystick::buttonActions() const
1571{
1572 QStringList list;
1573
1574 list.reserve(_totalButtonCount);
1575
1576 for (int button = 0; button < _totalButtonCount; button++) {
1577 if (_assignedButtonActions[button]) {
1578 list << _assignedButtonActions[button]->actionName;
1579 } else {
1580 list << _buttonActionNone;
1581 }
1582 }
1583
1584 return list;
1585}
1586
1587void Joystick::_executeButtonAction(const QString &action, const ButtonEvent_t buttonEvent)
1588{
1589 Vehicle *const vehicle = _pollingVehicle;
1590 if (!vehicle) {
1591 qCWarning(JoystickLog) << "Internal Error: No vehicle for joystick!";
1592 return;
1593 }
1594 if (!_joystickManager->activeJoystickEnabledForActiveVehicle()) {
1595 qCWarning(JoystickLog) << "Internal Error: Joystick not enabled for vehicle!";
1596 return;
1597 }
1598 if (action == _buttonActionNone) {
1599 return;
1600 }
1601
1602 const int idx = _findAvailableButtonActionIndex(action);
1603 if (idx >= 0) {
1604 const AvailableButtonAction *const availAction = qobject_cast<const AvailableButtonAction*>(_availableButtonActions->get(idx));
1605 std::function<void()> handler;
1606 switch (buttonEvent) {
1608 handler = availAction->onDown();
1609 break;
1610 case ButtonEventRepeat:
1611 handler = availAction->onRepeat();
1612 break;
1614 handler = availAction->onUp();
1615 break;
1616 default:
1617 return;
1618 }
1619 if (handler) {
1620 qCDebug(JoystickLog) << "Button Action:" << action << buttonEvent;
1621 handler();
1622 return;
1623 }
1624 // No lambda for this event — only DownTransition falls through to flight mode / MAVLink handling
1625 if (buttonEvent != ButtonEventDownTransition) {
1626 return;
1627 }
1628 }
1629
1630 if (buttonEvent != ButtonEventDownTransition) {
1631 return;
1632 }
1633
1634 // Flight mode check
1635 if (vehicle->flightModes().contains(action)) {
1636 qCDebug(JoystickLog) << "Button Action: Switching flight mode to" << action;
1637 emit setFlightMode(action);
1638 return;
1639 }
1640
1641 // MAVLink actions
1642 emit unknownAction(action);
1643 for (int i = 0; i < _mavlinkActionManager->actions()->count(); i++) {
1644 MavlinkAction *const mavlinkAction = _mavlinkActionManager->actions()->value<MavlinkAction*>(i);
1645 if (action == mavlinkAction->label()) {
1646 qCDebug(JoystickLog) << "Button Action: Sending MAVLink action" << action;
1647 mavlinkAction->sendTo(vehicle);
1648 return;
1649 }
1650 }
1651}
1652
1653bool Joystick::_validAxis(int axis) const
1654{
1655 if ((axis >= 0) && (axis < _axisCount)) {
1656 return true;
1657 }
1658
1659 qCWarning(JoystickLog) << "Invalid axis index" << axis;
1660 return false;
1661}
1662
1663bool Joystick::_validButton(int button) const
1664{
1665 if ((button >= 0) && (button < _totalButtonCount)) {
1666 return true;
1667 }
1668
1669 qCWarning(JoystickLog) << "Invalid button index" << button;
1670 return false;
1671}
1672
1673int Joystick::_findAvailableButtonActionIndex(const QString &action)
1674{
1675 for (int i = 0; i < _availableButtonActions->count(); i++) {
1676 const AvailableButtonAction *const buttonAction = qobject_cast<const AvailableButtonAction*>(_availableButtonActions->get(i));
1677 if (buttonAction->action() == action) {
1678 return i;
1679 }
1680 }
1681
1682 return -1;
1683}
1684
1685void Joystick::_buildAvailableButtonsActionList(Vehicle *vehicle)
1686{
1687 if (_availableButtonActions->count()) {
1688 _availableButtonActions->clearAndDeleteContents();
1689 }
1690 _availableActionTitles.clear();
1691
1692 _availableButtonActions->append(new AvailableButtonAction(_buttonActionNone, nullptr));
1693 _availableButtonActions->append(new AvailableButtonAction(_buttonActionArm,
1694 [this]() { emit setArmed(true); }));
1695 _availableButtonActions->append(new AvailableButtonAction(_buttonActionDisarm,
1696 [this]() { emit setArmed(false); }));
1697 _availableButtonActions->append(new AvailableButtonAction(_buttonActionToggleArm,
1698 [this]() { emit setArmed(!_pollingVehicle->armed()); }));
1699 if (vehicle) {
1700 const QStringList list = vehicle->flightModes();
1701 for (const QString &mode : list) {
1702 _availableButtonActions->append(new AvailableButtonAction(mode, nullptr));
1703 }
1704 }
1705
1706 _availableButtonActions->append(new AvailableButtonAction(_buttonActionVTOLFixedWing,
1707 [this]() { emit setVtolInFwdFlight(true); }));
1708 _availableButtonActions->append(new AvailableButtonAction(_buttonActionVTOLMultiRotor,
1709 [this]() { emit setVtolInFwdFlight(false); }));
1710 _availableButtonActions->append(new AvailableButtonAction(_buttonActionContinuousZoomIn,
1711 [this]() { emit startContinuousZoom(1); },
1712 [this]() { emit stopContinuousZoom(); }));
1713 _availableButtonActions->append(new AvailableButtonAction(_buttonActionContinuousZoomOut,
1714 [this]() { emit startContinuousZoom(-1); },
1715 [this]() { emit stopContinuousZoom(); }));
1716 _availableButtonActions->append(new AvailableButtonAction(_buttonActionStepZoomIn,
1717 [this]() { emit stepZoom(1); },
1718 nullptr,
1719 [this]() { emit stepZoom(1); }));
1720 _availableButtonActions->append(new AvailableButtonAction(_buttonActionStepZoomOut,
1721 [this]() { emit stepZoom(-1); },
1722 nullptr,
1723 [this]() { emit stepZoom(-1); }));
1724 _availableButtonActions->append(new AvailableButtonAction(_buttonActionContinuousFocusIn,
1725 [this]() { emit startContinuousFocus(1); },
1726 [this]() { emit stopContinuousFocus(); }));
1727 _availableButtonActions->append(new AvailableButtonAction(_buttonActionContinuousFocusOut,
1728 [this]() { emit startContinuousFocus(-1); },
1729 [this]() { emit stopContinuousFocus(); }));
1730 _availableButtonActions->append(new AvailableButtonAction(_buttonActionStepFocusIn,
1731 [this]() { emit stepFocus(1); },
1732 nullptr,
1733 [this]() { emit stepFocus(1); }));
1734 _availableButtonActions->append(new AvailableButtonAction(_buttonActionStepFocusOut,
1735 [this]() { emit stepFocus(-1); },
1736 nullptr,
1737 [this]() { emit stepFocus(-1); }));
1738 _availableButtonActions->append(new AvailableButtonAction(_buttonActionNextStream,
1739 [this]() { emit stepStream(1); }));
1740 _availableButtonActions->append(new AvailableButtonAction(_buttonActionPreviousStream,
1741 [this]() { emit stepStream(-1); }));
1742 _availableButtonActions->append(new AvailableButtonAction(_buttonActionNextCamera,
1743 [this]() { emit stepCamera(1); }));
1744 _availableButtonActions->append(new AvailableButtonAction(_buttonActionPreviousCamera,
1745 [this]() { emit stepCamera(-1); }));
1746 _availableButtonActions->append(new AvailableButtonAction(_buttonActionTriggerCamera,
1747 [this]() { emit triggerCamera(); }));
1748 _availableButtonActions->append(new AvailableButtonAction(_buttonActionStartVideoRecord,
1749 [this]() { emit startVideoRecord(); }));
1750 _availableButtonActions->append(new AvailableButtonAction(_buttonActionStopVideoRecord,
1751 [this]() { emit stopVideoRecord(); }));
1752 _availableButtonActions->append(new AvailableButtonAction(_buttonActionToggleVideoRecord,
1753 [this]() { emit toggleVideoRecord(); }));
1754 _availableButtonActions->append(new AvailableButtonAction(_buttonActionGimbalDown,
1755 [this]() { emit gimbalPitchStart(-1); },
1756 [this]() { emit gimbalPitchStop(); }));
1757 _availableButtonActions->append(new AvailableButtonAction(_buttonActionGimbalUp,
1758 [this]() { emit gimbalPitchStart(1); },
1759 [this]() { emit gimbalPitchStop(); }));
1760 _availableButtonActions->append(new AvailableButtonAction(_buttonActionGimbalLeft,
1761 [this]() { emit gimbalYawStart(-1); },
1762 [this]() { emit gimbalYawStop(); }));
1763 _availableButtonActions->append(new AvailableButtonAction(_buttonActionGimbalRight,
1764 [this]() { emit gimbalYawStart(1); },
1765 [this]() { emit gimbalYawStop(); }));
1766 _availableButtonActions->append(new AvailableButtonAction(_buttonActionGimbalCenter,
1767 [this]() { emit centerGimbal(); }));
1768 _availableButtonActions->append(new AvailableButtonAction(_buttonActionGimbalYawLock,
1769 [this]() { emit gimbalYawLock(true); }));
1770 _availableButtonActions->append(new AvailableButtonAction(_buttonActionGimbalYawFollow,
1771 [this]() { emit gimbalYawLock(false); }));
1772 _availableButtonActions->append(new AvailableButtonAction(_buttonActionEmergencyStop,
1773 [this]() { emit emergencyStop(); }));
1774 _availableButtonActions->append(new AvailableButtonAction(_buttonActionGripperGrab,
1775 [this]() { emit gripperAction(GRIPPER_ACTION_GRAB); }));
1776 _availableButtonActions->append(new AvailableButtonAction(_buttonActionGripperRelease,
1777 [this]() { emit gripperAction(GRIPPER_ACTION_RELEASE); }));
1778 _availableButtonActions->append(new AvailableButtonAction(_buttonActionGripperHold,
1779 [this]() { emit gripperAction(GRIPPER_ACTION_HOLD); }));
1780 _availableButtonActions->append(new AvailableButtonAction(_buttonActionLandingGearDeploy,
1781 [this]() { emit landingGearDeploy(); }));
1782 _availableButtonActions->append(new AvailableButtonAction(_buttonActionLandingGearRetract,
1783 [this]() { emit landingGearRetract(); }));
1784#ifndef QGC_NO_ARDUPILOT_DIALECT
1785 _availableButtonActions->append(new AvailableButtonAction(_buttonActionMotorInterlockEnable,
1786 [this]() { emit motorInterlock(true); }));
1787 _availableButtonActions->append(new AvailableButtonAction(_buttonActionMotorInterlockDisable,
1788 [this]() { emit motorInterlock(false); }));
1789#endif
1790
1791 const auto customActions = QGCCorePlugin::instance()->joystickActions();
1792 for (const auto &action : customActions) {
1793 // onDown is nullptr — dispatch falls through to unknownAction (DownTransition only).
1794 // A non-null onRepeat makes canRepeat() return true, preserving the UI toggle,
1795 // but custom plugin repeat dispatch is not supported (unknownAction carries no event type).
1796 std::function<void()> repeatFn = action.canRepeat ? std::function<void()>([]{}) : nullptr;
1797 _availableButtonActions->append(new AvailableButtonAction(action.name, nullptr, nullptr, repeatFn));
1798 }
1799
1800 for (int i = 0; i < _mavlinkActionManager->actions()->count(); i++) {
1801 const MavlinkAction *const mavlinkAction = _mavlinkActionManager->actions()->value<const MavlinkAction*>(i);
1802 _availableButtonActions->append(new AvailableButtonAction(mavlinkAction->label(), nullptr));
1803 }
1804
1805 for (int i = 0; i < _availableButtonActions->count(); i++) {
1806 const AvailableButtonAction *const buttonAction = qobject_cast<const AvailableButtonAction*>(_availableButtonActions->get(i));
1807 _availableActionTitles << buttonAction->action();
1808 }
1809
1811}
1812
1814{
1815 switch (function) {
1816 case rollFunction:
1817 return QStringLiteral("Roll");
1818 case pitchFunction:
1819 return QStringLiteral("Pitch");
1820 case yawFunction:
1821 return QStringLiteral("Yaw");
1822 case throttleFunction:
1823 return QStringLiteral("Throttle");
1825 return QStringLiteral("Additional Axis 1");
1827 return QStringLiteral("Additional Axis 2");
1829 return QStringLiteral("Additional Axis 3");
1831 return QStringLiteral("Additional Axis 4");
1833 return QStringLiteral("Additional Axis 5");
1835 return QStringLiteral("Additional Axis 6");
1837 return QStringLiteral("Pitch Extension");
1839 return QStringLiteral("Roll Extension");
1840 case maxAxisFunction:
1841 return QStringLiteral("Unassigned");
1842 }
1843 Q_UNREACHABLE();
1844}
1845
1847{
1848 _startPollingForConfiguration();
1849}
1850
1852{
1853 _stopPollingForConfiguration();
1854}
1855
1856Joystick::AxisFunction_t Joystick::_getAxisFunctionForJoystickAxis(int joystickAxis) const
1857{
1858 if (!_validAxis(joystickAxis)) {
1859 return maxAxisFunction;
1860 }
1861
1862 for (int i = 0; i < maxAxisFunction; i++) {
1863 auto axisFunction = static_cast<AxisFunction_t>(i);
1864 if (_axisFunctionToJoystickAxisMap.value(axisFunction, kJoystickAxisNotAssigned) == joystickAxis) {
1865 return axisFunction;
1866 }
1867 }
1868
1869 return maxAxisFunction;
1870}
1871
1873{
1874 _exitPollingThread = true;
1875 if (isRunning()) {
1876 if (QThread::currentThread() == this) {
1877 qCWarning(JoystickLog) << "Skipping wait() on joystick thread";
1878 } else {
1879 wait();
1880 }
1881 }
1882}
1883
1884void Joystick::setLinkedGroupId(const QString &groupId)
1885{
1886 if (_linkedGroupId != groupId) {
1887 _linkedGroupId = groupId;
1888
1889 // Persist to settings
1890 QSettings settings;
1891 settings.beginGroup(QStringLiteral("Joystick"));
1892 settings.beginGroup(_name);
1893 if (groupId.isEmpty()) {
1894 settings.remove(QStringLiteral("LinkedGroupId"));
1895 } else {
1896 settings.setValue(QStringLiteral("LinkedGroupId"), groupId);
1897 }
1898 settings.endGroup();
1899 settings.endGroup();
1900
1901 emit linkedGroupChanged();
1902 }
1903}
1904
1905void Joystick::setLinkedGroupRole(const QString &role)
1906{
1907 if (_linkedGroupRole != role) {
1908 _linkedGroupRole = role;
1909
1910 // Persist to settings
1911 QSettings settings;
1912 settings.beginGroup(QStringLiteral("Joystick"));
1913 settings.beginGroup(_name);
1914 if (role.isEmpty()) {
1915 settings.remove(QStringLiteral("LinkedGroupRole"));
1916 } else {
1917 settings.setValue(QStringLiteral("LinkedGroupRole"), role);
1918 }
1919 settings.endGroup();
1920 settings.endGroup();
1921
1922 emit linkedGroupChanged();
1923 }
1924}
#define QGC_LOGGING_CATEGORY(name, categoryStr)
AssignedButtonAction(const QString &name, bool repeat)
Definition Joystick.cc:54
const std::function< void()> & onUp() const
Definition Joystick.h:50
const QString & action() const
Definition Joystick.h:46
const std::function< void()> & onDown() const
Definition Joystick.h:48
const std::function< void()> & onRepeat() const
Definition Joystick.h:49
AvailableButtonAction(const QString &actionName, std::function< void()> onDown, std::function< void()> onUp=nullptr, std::function< void()> onRepeat=nullptr, QObject *parent=nullptr)
Definition Joystick.cc:61
bool canRepeat() const
Definition Joystick.h:47
A Fact is used to hold a single value within the system.
Definition Fact.h:17
void rawValueChanged(const QVariant &value)
Q_INVOKABLE void centerGimbal()
void gimbalYawLock(bool yawLock)
void gimbalYawStart(int direction)
void gimbalPitchStart(int direction)
bool activeJoystickEnabledForActiveVehicle() const
static JoystickManager * instance()
void setActiveJoystickEnabledForActiveVehicle(bool enabled)
void setLinkedGroupId(const QString &groupId)
Definition Joystick.cc:1884
Q_INVOKABLE void stopConfiguration()
Tells the joystick that the configuration UI is being closed so it can do any special processing requ...
Definition Joystick.cc:1851
void rawButtonPressedChanged(int index, bool pressed)
Signalled during PollingForConfiguration.
void setArmed(bool arm)
void gimbalYawLock(bool lock)
int _buttonCount
Definition Joystick.h:388
void triggerCamera()
virtual ~Joystick()
Definition Joystick.cc:165
@ pitchExtensionFunction
Definition Joystick.h:142
@ additionalAxis2Function
Definition Joystick.h:145
@ rollFunction
Definition Joystick.h:138
@ yawFunction
Definition Joystick.h:140
@ additionalAxis6Function
Definition Joystick.h:149
@ additionalAxis3Function
Definition Joystick.h:146
@ additionalAxis4Function
Definition Joystick.h:147
@ maxAxisFunction
Definition Joystick.h:150
@ additionalAxis1Function
Definition Joystick.h:144
@ additionalAxis5Function
Definition Joystick.h:148
@ throttleFunction
Definition Joystick.h:141
@ rollExtensionFunction
Definition Joystick.h:143
@ pitchFunction
Definition Joystick.h:139
QString name() const
Definition Joystick.h:205
Joystick(const QString &name, int axisCount, int buttonCount, int hatCount, QObject *parent=nullptr)
Definition Joystick.cc:73
void stopContinuousFocus()
RemoteControlCalibrationController::StickFunction mapAxisFunctionToRCCStickFunction(AxisFunction_t axisFunction) const
Definition Joystick.cc:1406
void startVideoRecord()
QString _name
Definition Joystick.h:386
int _hatCount
Definition Joystick.h:389
void setLinkedGroupRole(const QString &role)
Definition Joystick.cc:1905
void setFlightMode(const QString &flightMode)
void motorInterlock(bool enable)
static QString axisFunctionToString(AxisFunction_t function)
Definition Joystick.cc:1813
void setFunctionForChannel(RemoteControlCalibrationController::StickFunction stickFunction, int channel)
Definition Joystick.cc:1472
void axisValues(float roll, float pitch, float yaw, float throttle)
void landingGearDeploy()
void buttonActionsChanged()
void stop()
Definition Joystick.cc:1872
int axisCount() const
Definition Joystick.h:207
@ ButtonEventDownTransition
Definition Joystick.h:116
@ ButtonEventNone
Definition Joystick.h:118
@ ButtonEventRepeat
Definition Joystick.h:117
@ ButtonEventUpTransition
Definition Joystick.h:115
void assignableActionsChanged()
void centerGimbal()
void unknownAction(const QString &action)
int getChannelForFunction(RemoteControlCalibrationController::StickFunction stickFunction) const
Definition Joystick.cc:1477
Q_INVOKABLE QString getButtonAction(int button) const
Definition Joystick.cc:1559
void stopVideoRecord()
void stepZoom(int direction)
QStringList buttonActions() const
Definition Joystick.cc:1570
AxisFunction_t mapRCCStickFunctionToAxisFunction(RemoteControlCalibrationController::StickFunction stickFunction) const
Definition Joystick.cc:1439
Q_INVOKABLE void startConfiguration()
Tells the joystick that the configuration UI is being displayed so it can do any special processing r...
Definition Joystick.cc:1846
Joystick::AxisCalibration_t getAxisCalibration(int axis) const
Definition Joystick.cc:1369
void setAxisCalibration(int axis, const AxisCalibration_t &calibration)
Definition Joystick.cc:1360
void gimbalPitchStop()
int _axisCount
Definition Joystick.h:387
void gimbalYawStop()
void startContinuousZoom(int direction)
JoystickSettings * settings()
Definition Joystick.h:204
void stopContinuousZoom()
void emergencyStop()
Q_INVOKABLE bool getButtonRepeat(int button)
Definition Joystick.cc:1502
int buttonCount() const
Definition Joystick.h:206
Q_INVOKABLE void setButtonAction(int button, const QString &action)
Definition Joystick.cc:1511
void stepCamera(int direction)
void setVtolInFwdFlight(bool set)
void gripperAction(GRIPPER_ACTIONS gripperAction)
void stepStream(int direction)
void landingGearRetract()
void toggleVideoRecord()
void stepFocus(int direction)
void gimbalPitchStart(int direction)
void linkedGroupChanged()
void rawChannelValuesChanged(QVector< int > channelValues)
Signalled during PollingForConfiguration.
void startContinuousFocus(int direction)
void gimbalYawStart(int direction)
Q_INVOKABLE void setButtonRepeat(int button, bool repeat)
Definition Joystick.cc:1482
Loads the specified action file and provides access to the actions it contains.
QmlObjectListModel * actions()
const QString & label() const
Q_INVOKABLE void sendTo(Vehicle *vehicle)
static MultiVehicleManager * instance()
Vehicle * activeVehicle() const
virtual QList< JoystickAction > joystickActions()
static QGCCorePlugin * instance()
void append(QObject *object)
Caller maintains responsibility for object ownership and deletion.
T value(int index) const
Q_INVOKABLE QObject * get(int index)
int count() const override final
void clearAndDeleteContents() override final
Clears the list and calls deleteLater on each entry.
StickFunction
These identify the various controls functions. They are also used as indices into the _rgFunctioInfo ...
QString settingsGroup() const
Provides access to all app settings.
bool negativeThrust() const
bool throttleModeCenterZero() const
Q_INVOKABLE void motorInterlock(bool enable)
Command vehicle to Enable/Disable Motor Interlock.
Definition Vehicle.cc:3371
Q_INVOKABLE void sendGripperAction(GRIPPER_ACTIONS gripperOption)
Definition Vehicle.cc:3137
void sendJoystickAuxRcOverrideThreadSafe(const std::array< uint16_t, kAuxRcOverrideChannelCount > &channelValues, const std::array< bool, kAuxRcOverrideChannelCount > &channelEnabled, bool useRcOverride)
Definition Vehicle.cc:3041
Q_INVOKABLE void emergencyStop()
Command vehicle to kill all motors no matter what state.
Definition Vehicle.cc:2081
int id() const
Definition Vehicle.h:425
void setFlightMode(const QString &flightMode)
Definition Vehicle.cc:1478
Q_INVOKABLE void landingGearDeploy()
Command vichecle to deploy landing gear.
Definition Vehicle.cc:2091
void flightModesChanged()
GimbalController * gimbalController()
Definition Vehicle.h:731
void setVtolInFwdFlight(bool vtolInFwdFlight)
Definition Vehicle.cc:2457
void sendJoystickDataThreadSafe(float roll, float pitch, float yaw, float thrust, quint16 buttons, quint16 buttons2, float pitchExtension, float rollExtension, float aux1, float aux2, float aux3, float aux4, float aux5, float aux6)
Definition Vehicle.cc:2981
bool armed() const
Definition Vehicle.h:449
Q_INVOKABLE void landingGearRetract()
Command vichecle to retract landing gear.
Definition Vehicle.cc:2101
VehicleSupports * supports()
Definition Vehicle.h:402
QStringList flightModes()
Definition Vehicle.cc:1462
void setArmedShowError(bool armed)
Definition Vehicle.h:451