17#include <QtCore/QCoreApplication>
21#include <QtCore/QSettings>
22#include <QtCore/QThread>
27static QDebug operator<<(QDebug debug,
Joystick::ButtonEvent_t event)
35 return debug << static_cast<int>(event);
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";
55 : actionName(actionName_)
58 qCDebug(JoystickVerboseLog) <<
this;
63 , _actionName(actionName_)
64 , _onDown(std::move(onDown_))
65 , _onRepeat(std::move(onRepeat_))
66 , _onUp(std::move(onUp_))
68 qCDebug(JoystickVerboseLog) <<
this;
73Joystick::Joystick(
const QString &name,
int axisCount,
int buttonCount,
int hatCount, QObject *parent)
76 , _axisCount(axisCount)
77 , _buttonCount(buttonCount)
79 , _hatButtonCount(4 * hatCount)
80 , _totalButtonCount(_buttonCount + _hatButtonCount)
81 , _rgCalibration(_axisCount)
82 , _buttonEventStates(_totalButtonCount)
83 , _assignedButtonActions(_totalButtonCount, nullptr)
87 , _joystickSettings(name, _axisCount, _totalButtonCount)
93 <<
"hatCount:" << hatCount
96 if (QCoreApplication *
const app = QCoreApplication::instance()) {
97 QThread *
const guiThread = app->thread();
98 if (_joystickSettings.thread() != guiThread) {
99 _joystickSettings.moveToThread(guiThread);
102 const auto ensureFactThread = [guiThread](
Fact *fact) {
103 if (fact && fact->thread() != guiThread) {
104 fact->moveToThread(guiThread);
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());
130 connect(_joystickSettings.enableManualControlPitchExtension(), &
Fact::rawValueChanged,
this, [
this]() {
131 _joystickSettings.calibrated()->setRawValue(false);
133 connect(_joystickSettings.enableManualControlRollExtension(), &
Fact::rawValueChanged,
this, [
this]() {
134 _joystickSettings.calibrated()->setRawValue(false);
137 _joystickSettings.calibrated()->setRawValue(false);
140 _joystickSettings.calibrated()->setRawValue(false);
143 _joystickSettings.calibrated()->setRawValue(false);
146 _joystickSettings.calibrated()->setRawValue(false);
149 _joystickSettings.calibrated()->setRawValue(false);
152 _joystickSettings.calibrated()->setRawValue(false);
155 _resetFunctionToAxisMap();
156 _resetAxisCalibrationData();
157 _resetButtonActionData();
158 _resetButtonEventStates();
162 _loadFromSettingsIntoCalibrationData();
167 _exitPollingThread =
true;
169 if (QThread::currentThread() ==
this) {
170 qCWarning(JoystickLog) <<
"Skipping wait() on joystick thread";
176 _resetButtonActionData();
180void Joystick::_resetFunctionToAxisMap()
182 _axisFunctionToJoystickAxisMap.clear();
184 _axisFunctionToJoystickAxisMap[
static_cast<AxisFunction_t>(i)] = kJoystickAxisNotAssigned;
188void Joystick::_resetAxisCalibrationData()
190 _resetFunctionToAxisMap();
191 for (
int axis = 0; axis <
_axisCount; axis++) {
192 auto& calibration = _rgCalibration[axis];
197void Joystick::_resetButtonActionData()
199 for (
int i = 0; i < _assignedButtonActions.count(); i++) {
200 delete _assignedButtonActions[i];
201 _assignedButtonActions[i] =
nullptr;
205void Joystick::_resetButtonEventStates()
207 for (
int i = 0; i < _buttonEventStates.count(); i++) {
212void Joystick::_loadButtonSettings()
214 const QString actionNameKey = QString::fromLatin1(kButtonActionNameKey);
215 const QString repeatKey = QString::fromLatin1(kButtonRepeatKey);
217 QSettings buttonSettings;
218 buttonSettings.beginGroup(_joystickSettings.
settingsGroup());
220 if (buttonSettings.childGroups().contains(QString::fromLatin1(kButtonActionArrayGroup))) {
221 buttonSettings.beginGroup(QString::fromLatin1(kButtonActionArrayGroup));
223 qCDebug(JoystickLog) <<
"Button Actions:";
225 bool foundButton =
false;
226 for (
int buttonIndex = 0; buttonIndex < _totalButtonCount; buttonIndex++) {
227 if (!buttonSettings.childGroups().contains(QString::number(buttonIndex))) {
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();
236 if (actionName.isEmpty()) {
237 qCWarning(JoystickLog)
239 <<
"button:" << buttonIndex
240 <<
"has empty action name, clearing action from data";
241 buttonSettings.remove(QString::number(buttonIndex));
244 if (_findAvailableButtonActionIndex(actionName) == -1) {
245 qCWarning(JoystickLog)
247 <<
"button:" << buttonIndex
248 <<
"has unknown action name:" << actionName
249 <<
", clearing action from data";
250 buttonSettings.remove(QString::number(buttonIndex));
253 if (actionName == _buttonActionNone) {
254 buttonSettings.remove(QString::number(buttonIndex));
259 _assignedButtonActions[buttonIndex] = buttonAction;
260 _assignedButtonActions[buttonIndex]->buttonElapsedTimer.start();
265 <<
"button:" << buttonIndex
266 <<
"actionName:" << actionName
267 <<
"repeat:" << repeat;
270 buttonSettings.endGroup();
273 buttonSettings.remove(QString::fromLatin1(kButtonActionArrayGroup));
278void Joystick::_foundInvalidAxisSettingsCleanup()
280 _clearAxisSettings();
281 _resetAxisCalibrationData();
282 _joystickSettings.calibrated()->setRawValue(
false);
285void Joystick::_loadAxisSettings(
bool joystickCalibrated,
int transmitterMode)
287 QSettings axisSettings;
292 if (!joystickCalibrated) {
293 _clearAxisSettings();
294 _resetAxisCalibrationData();
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);
305 qCDebug(JoystickLog) <<
"Axis Settings:";
307 axisSettings.beginGroup(QString::fromLatin1(kAxisSettingsArrayGroup));
308 for (
int axis = 0; axis <
_axisCount; axis++) {
309 if (!axisSettings.childGroups().contains(QString::number(axis))) {
313 <<
"no settings found, skipping";
317 axisSettings.beginGroup(QString::number(axis));
319 auto& axisCalibration = _rgCalibration[axis];
321 const int axisFunction = axisSettings.value(functionKey,
maxAxisFunction).toInt();
323 qCWarning(JoystickLog) <<
"Invalid function" << axisFunction <<
"for axis" << axis;
324 axisSettings.endGroup();
329 axisSettings.endGroup();
332 _setJoystickAxisForAxisFunction(
static_cast<AxisFunction_t>(axisFunction), axis);
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();
343 <<
"min:" << axisCalibration.min
344 <<
"max:" << axisCalibration.max
345 <<
"center:" << axisCalibration.center
346 <<
"reversed:" << axisCalibration.reversed
347 <<
"deadband:" << axisCalibration.deadband
350 axisSettings.endGroup();
352 axisSettings.endGroup();
355 bool rollFunctionNotAssigned = _axisFunctionToJoystickAxisMap[
rollFunction] == kJoystickAxisNotAssigned;
356 if (rollFunctionNotAssigned) {
357 qCWarning(JoystickLog) <<
"Roll axis function not assigned";
359 bool pitchFunctionNotAssigned = _axisFunctionToJoystickAxisMap[
pitchFunction] == kJoystickAxisNotAssigned;
360 if (pitchFunctionNotAssigned) {
361 qCWarning(JoystickLog) <<
"Pitch axis function not assigned";
363 bool yawFunctionNotAssigned = _axisFunctionToJoystickAxisMap[
yawFunction] == kJoystickAxisNotAssigned;
364 if (yawFunctionNotAssigned) {
365 qCWarning(JoystickLog) <<
"Yaw axis function not assigned";
367 bool throttleFunctionNotAssigned = _axisFunctionToJoystickAxisMap[
throttleFunction] == kJoystickAxisNotAssigned;
368 if (throttleFunctionNotAssigned) {
369 qCWarning(JoystickLog) <<
"Throttle axis function not assigned";
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!";
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!";
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!";
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!";
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!";
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!";
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!";
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!";
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);
441 _remapFunctionsInFunctionMapToNewTransmittedMode(2, transmitterMode);
444void Joystick::_loadFromSettingsIntoCalibrationData()
446 _resetAxisCalibrationData();
447 _resetButtonActionData();
451 bool calibrated = _joystickSettings.calibrated()->rawValue().toBool();
452 int transmitterMode = _joystickSettings.transmitterMode()->rawValue().toInt();
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();
475 _loadAxisSettings(calibrated, transmitterMode);
476 _loadButtonSettings();
479void Joystick::_saveAxisSettings(
int transmitterMode)
481 qCDebug(JoystickLog) <<
name();
485 _remapFunctionsInFunctionMapToNewTransmittedMode(transmitterMode, 2);
487 QSettings axisSettings;
489 axisSettings.beginGroup(QString::fromLatin1(kAxisSettingsArrayGroup));
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);
498 for (
int axis = 0; axis <
_axisCount; axis++) {
504 AxisCalibration_t *
const calibration = &_rgCalibration[axis];
505 axisSettings.beginGroup(QString::number(axis));
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));
517 <<
"min:" << calibration->min
518 <<
"max:" << calibration->max
519 <<
"center:" << calibration->center
520 <<
"reversed:" << calibration->reversed
521 <<
"deadband:" << calibration->deadband
524 axisSettings.endGroup();
527 axisSettings.endGroup();
528 axisSettings.endGroup();
531 _remapFunctionsInFunctionMapToNewTransmittedMode(2, transmitterMode);
534void Joystick::_saveButtonSettings()
536 qCDebug(JoystickLog) <<
name();
538 const QString actionNameKey = QString::fromLatin1(kButtonActionNameKey);
539 const QString repeatKey = QString::fromLatin1(kButtonRepeatKey);
541 QSettings buttonSettings;
542 buttonSettings.beginGroup(_joystickSettings.
settingsGroup());
543 buttonSettings.beginGroup(QString::fromLatin1(kButtonActionArrayGroup));
545 bool anyButtonsSaved =
false;
546 for (
int buttonIndex = 0; buttonIndex < _totalButtonCount; buttonIndex++) {
550 buttonSettings.beginGroup(QString::number(buttonIndex));
551 buttonSettings.setValue(actionNameKey, buttonAction->
actionName);
552 buttonSettings.setValue(repeatKey, buttonAction->
repeat);
553 buttonSettings.endGroup();
555 anyButtonsSaved =
true;
559 <<
"button:" << buttonIndex
561 <<
"repeat:" << buttonAction->
repeat;
564 buttonSettings.remove(QString::number(buttonIndex));
568 buttonSettings.endGroup();
569 buttonSettings.endGroup();
571 if (!anyButtonsSaved) {
572 qCDebug(JoystickLog) <<
" No button actions to save, cleared button action settings.";
573 _clearButtonSettings();
577void Joystick::_clearAxisSettings()
579 QSettings axisSettings;
581 axisSettings.remove(QString::fromLatin1(kAxisSettingsArrayGroup));
582 axisSettings.endGroup();
585void Joystick::_clearButtonSettings()
587 QSettings buttonSettings;
588 buttonSettings.beginGroup(_joystickSettings.
settingsGroup());
589 buttonSettings.remove(QString::fromLatin1(kButtonActionArrayGroup));
590 buttonSettings.endGroup();
593void Joystick::_saveFromCalibrationDataIntoSettings()
595 bool calibrated = _joystickSettings.calibrated()->rawValue().toBool();
596 int transmitterMode = _joystickSettings.transmitterMode()->rawValue().toInt();
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;
619 _clearAxisSettings();
621 _saveAxisSettings(transmitterMode);
624 _clearButtonSettings();
625 _saveButtonSettings();
628void Joystick::_remapFunctionsInFunctionMapToNewTransmittedMode(
int fromMode,
int toMode)
630 static constexpr const int modeCount = 4;
631 static constexpr const int attitudeControlCount = 4;
632 static constexpr const AxisFunction_t mapping[modeCount][attitudeControlCount] = {
640 AxisFunctionMap_t tempMap = _axisFunctionToJoystickAxisMap;
642 for (
int i=0; i<attitudeControlCount; i++) {
643 auto fromAxisFunction = mapping[fromMode - 1][i];
644 auto toAxisFunction = mapping[toMode - 1][i];
646 tempMap[toAxisFunction] = _axisFunctionToJoystickAxisMap[fromAxisFunction];
651 _axisFunctionToJoystickAxisMap[axisFunction] = tempMap[axisFunction];
657 bool openFailed =
false;
658 bool updateFailed =
false;
661 qCWarning(JoystickLog) <<
"Failed to open joystick:" <<
_name;
666 _axisElapsedTimer.start();
668 for (
int buttonIndex = 0; buttonIndex < _totalButtonCount; buttonIndex++) {
669 if (_assignedButtonActions[buttonIndex]) {
670 _assignedButtonActions[buttonIndex]->buttonElapsedTimer.start();
674 while (!_exitPollingThread) {
676 qCWarning(JoystickLog) <<
"Joystick disconnected or update failed:" <<
_name;
687 const double axisFrequencyHz = _joystickSettings.axisFrequencyHz()->rawValue().toDouble();
688 const double buttonFrequencyHz = _joystickSettings.buttonFrequencyHz()->rawValue().toDouble();
690 const int sleep = qMin(
static_cast<int>(1000.0 / axisFrequencyHz),
static_cast<int>(1000.0 / buttonFrequencyHz)) / 2;
691 QThread::msleep(sleep);
697 if ((openFailed || updateFailed) && !_exitPollingThread) {
698 qCDebug(JoystickLog) <<
"Triggering joystick rescan after failure";
703void Joystick::_updateButtonEventState(
int buttonIndex,
const bool buttonPressed, ButtonEvent_t &buttonEventState)
707 qCDebug(JoystickLog) <<
"Button" << buttonIndex <<
"down transition";
710 qCDebug(JoystickLog) <<
"Button" << buttonIndex <<
"repeat";
715 qCDebug(JoystickLog) <<
"Button" << buttonIndex <<
"up transition";
718 qCDebug(JoystickLog) <<
"Button" << buttonIndex <<
"none";
724void Joystick::_updateButtonEventStates(QVector<ButtonEvent_t> &buttonEventStates)
726 if (buttonEventStates.size() < _totalButtonCount) {
727 qCWarning(JoystickLog) <<
"Internal Error: buttonEventStates size incorrect!";
732 for (
int buttonIndex = 0; buttonIndex <
_buttonCount; buttonIndex++) {
733 const bool buttonIsPressed = _getButton(buttonIndex);
734 _updateButtonEventState(buttonIndex, buttonIsPressed, buttonEventStates[buttonIndex]);
738 const int numHatButtons = 4;
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]);
750void Joystick::_handleButtons()
752 if (_pollingFlags == PollingNone) {
753 qCWarning(JoystickLog) <<
"Internal Error: Joystick not polling!";
757 _updateButtonEventStates(_buttonEventStates);
759 if (_pollingFlags.testFlag(PollingForConfiguration)) {
760 for (
int buttonIndex = 0; buttonIndex < _totalButtonCount; buttonIndex++) {
762 qCDebug(JoystickLog) <<
"Button pressed - button" << buttonIndex;
765 qCDebug(JoystickLog) <<
"Button released - button" << buttonIndex;
769 }
else if (_pollingFlags.testFlag(PollingForVehicle)) {
770 Vehicle *
const vehicle = _pollingVehicle;
772 qCWarning(JoystickLog) <<
"Internal Error: No vehicle for joystick!";
776 qCWarning(JoystickLog) <<
"Internal Error: Joystick not enabled for vehicle!";
779 if (!_joystickSettings.calibrated()->rawValue().toBool()) {
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]) {
790 auto assignedAction = _assignedButtonActions[buttonIndex];
792 const QString buttonAction = assignedAction->
actionName;
793 if (buttonAction.isEmpty() || (buttonAction == _buttonActionNone)) {
797 auto buttonEventState = _buttonEventStates[buttonIndex];
799 if (assignedAction->repeat) {
800 if (assignedAction->buttonElapsedTimer.elapsed() > buttonDelay) {
801 assignedAction->buttonElapsedTimer.start();
802 qCDebug(JoystickLog) <<
"Repeat - button:action" << buttonIndex << buttonAction;
804 QMetaObject::invokeMethod(
this, [
this, buttonAction]() {
806 }, Qt::QueuedConnection);
811 QList<int> multiActionButtons = { buttonIndex };
812 bool allActionButtonsPressed =
true;
813 for (
int multiIndex = 0; multiIndex < _totalButtonCount; multiIndex++) {
814 if (multiIndex == buttonIndex) {
817 if (_assignedButtonActions[multiIndex] && (_assignedButtonActions[multiIndex]->actionName == buttonAction)) {
821 multiActionButtons.append(multiIndex);
824 allActionButtonsPressed =
false;
830 if (!allActionButtonsPressed) {
834 if (multiActionButtons.size() > 1) {
835 qCDebug(JoystickLog) <<
"Multi-button action - buttons:action" << multiActionButtons << buttonAction;
837 qCDebug(JoystickLog) <<
"Action triggered - button:Action" << buttonIndex << buttonAction;
842 if (!executedActions.contains(buttonAction)) {
844 QMetaObject::invokeMethod(
this, [
this, buttonAction]() {
846 }, Qt::QueuedConnection);
847 executedActions.insert(buttonAction);
854 if (!executedActions.contains(buttonAction)) {
856 QMetaObject::invokeMethod(
this, [
this, buttonAction]() {
858 }, Qt::QueuedConnection);
859 executedActions.insert(buttonAction);
867float Joystick::_adjustRange(
int value,
const AxisCalibration_t &calibration,
bool withDeadbands)
869 float valueNormalized;
873 if (calibration.center == calibration.min) {
875 valueNormalized =
static_cast<float>(std::max(0, value - calibration.center));
876 axisLength = calibration.max - calibration.center;
877 }
else if (calibration.center == calibration.max) {
879 valueNormalized =
static_cast<float>(std::max(0, calibration.center - value));
880 axisLength = calibration.center - calibration.min;
881 }
else if (value > calibration.center) {
883 valueNormalized = value - calibration.center;
884 axisLength = calibration.max - calibration.center;
887 valueNormalized = calibration.center - value;
888 axisLength = calibration.center - calibration.min;
891 if (axisLength <= 0.0f) {
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);
905 axisPercent = valueNormalized / axisLength;
908 float correctedValue = axisBasis * axisPercent;
909 if (calibration.reversed) {
910 correctedValue *= -1.0f;
913 return std::max(-1.0f, std::min(correctedValue, 1.0f));
916uint16_t Joystick::_adjustRangeToRcOverridePwm(
int value,
const AxisCalibration_t &calibration,
bool withDeadbands)
918 const float normalizedValue = _adjustRange(value, calibration, withDeadbands);
919 const bool oneSidedAxis = (calibration.center == calibration.min) || (calibration.center == calibration.max);
923 pwmValue = 1000.0f + (std::clamp(normalizedValue, 0.0f, 1.0f) * 1000.0f);
925 pwmValue = 1500.0f + (std::clamp(normalizedValue, -1.0f, 1.0f) * 500.0f);
928 return static_cast<uint16_t
>(std::lround(std::clamp(pwmValue, 1000.0f, 2000.0f)));
931void Joystick::_handleAxis()
933 const int axisDelay =
static_cast<int>(1000.0 / _joystickSettings.axisFrequencyHz()->rawValue().toDouble());
934 if (_axisElapsedTimer.elapsed() <= axisDelay) {
938 _axisElapsedTimer.start();
940 if (_pollingFlags == PollingNone) {
941 qCWarning(JoystickLog) <<
"Internal Error: Joystick not polling!";
945 if (_pollingFlags.testFlag(PollingForConfiguration)) {
949 for (
int axisIndex = 0; axisIndex <
_axisCount; axisIndex++) {
950 channelValues[axisIndex] = _getAxisValue(axisIndex);
953 }
else if (_pollingFlags.testFlag(PollingForVehicle)) {
954 Vehicle *
const vehicle = _pollingVehicle;
956 qCWarning(JoystickLog) <<
"Internal Error: No vehicle for joystick!";
960 qCWarning(JoystickLog) <<
"Internal Error: Joystick not enabled for vehicle!";
963 if (!_joystickSettings.calibrated()->rawValue().toBool()) {
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();
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!";
982 int axisIndex = _getJoystickAxisForAxisFunction(
rollFunction);
983 float roll = _adjustRange(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband);
985 float pitch = _adjustRange(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband);
986 axisIndex = _getJoystickAxisForAxisFunction(
yawFunction);
987 float yaw = _adjustRange(_getAxisValue(axisIndex), _rgCalibration[axisIndex],useDeadband);
989 float throttle = _adjustRange(_getAxisValue(axisIndex), _rgCalibration[axisIndex], throttleModeCenterZero ? useDeadband : false);
991 float pitchExtension = qQNaN();
992 if (_joystickSettings.enableManualControlPitchExtension()->rawValue().toBool()) {
994 qCWarning(JoystickLog) <<
"Internal Error: Missing pitch extension axis function mapping!";
998 pitchExtension = _adjustRange(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband);
1000 float rollExtension = qQNaN();
1001 if (_joystickSettings.enableManualControlRollExtension()->rawValue().toBool()) {
1003 qCWarning(JoystickLog) <<
"Internal Error: Missing roll extension axis function mapping!";
1007 rollExtension = _adjustRange(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband);
1009 std::array<uint16_t, 6> auxRcOverridePwm{};
1010 std::array<bool, 6> auxRcOverrideEnabled{};
1012 float auxManualControl1 = qQNaN();
1013 if (_joystickSettings.enableAdditionalAxis1()->rawValue().toBool()) {
1015 qCWarning(JoystickLog) <<
"Internal Error: Missing additional axis 1 function mapping!";
1019 if (additionalAxesFunctionIsManualControl) {
1020 auxManualControl1 = _adjustRange(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband);
1022 auxRcOverridePwm[0] = _adjustRangeToRcOverridePwm(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband);
1023 auxRcOverrideEnabled[0] =
true;
1026 float auxManualControl2 = qQNaN();
1027 if (_joystickSettings.enableAdditionalAxis2()->rawValue().toBool()) {
1029 qCWarning(JoystickLog) <<
"Internal Error: Missing additional axis 2 function mapping!";
1033 if (additionalAxesFunctionIsManualControl) {
1034 auxManualControl2 = _adjustRange(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband);
1036 auxRcOverridePwm[1] = _adjustRangeToRcOverridePwm(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband);
1037 auxRcOverrideEnabled[1] =
true;
1040 float auxManualControl3 = qQNaN();
1041 if (_joystickSettings.enableAdditionalAxis3()->rawValue().toBool()) {
1043 qCWarning(JoystickLog) <<
"Internal Error: Missing additional axis 3 function mapping!";
1047 if (additionalAxesFunctionIsManualControl) {
1048 auxManualControl3 = _adjustRange(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband);
1050 auxRcOverridePwm[2] = _adjustRangeToRcOverridePwm(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband);
1051 auxRcOverrideEnabled[2] =
true;
1054 float auxManualControl4 = qQNaN();
1055 if (_joystickSettings.enableAdditionalAxis4()->rawValue().toBool()) {
1057 qCWarning(JoystickLog) <<
"Internal Error: Missing additional axis 4 function mapping!";
1061 if (additionalAxesFunctionIsManualControl) {
1062 auxManualControl4 = _adjustRange(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband);
1064 auxRcOverridePwm[3] = _adjustRangeToRcOverridePwm(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband);
1065 auxRcOverrideEnabled[3] =
true;
1068 float auxManualControl5 = qQNaN();
1069 if (_joystickSettings.enableAdditionalAxis5()->rawValue().toBool()) {
1071 qCWarning(JoystickLog) <<
"Internal Error: Missing additional axis 5 function mapping!";
1075 if (additionalAxesFunctionIsManualControl) {
1076 auxManualControl5 = _adjustRange(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband);
1078 auxRcOverridePwm[4] = _adjustRangeToRcOverridePwm(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband);
1079 auxRcOverrideEnabled[4] =
true;
1082 float auxManualControl6 = qQNaN();
1083 if (_joystickSettings.enableAdditionalAxis6()->rawValue().toBool()) {
1085 qCWarning(JoystickLog) <<
"Internal Error: Missing additional axis 6 function mapping!";
1089 if (additionalAxesFunctionIsManualControl) {
1090 auxManualControl6 = _adjustRange(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband);
1092 auxRcOverridePwm[5] = _adjustRangeToRcOverridePwm(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband);
1093 auxRcOverrideEnabled[5] =
true;
1097 if (throttleSmoothing) {
1098 static float throttleSmoothingValue = 0.f;
1099 throttleSmoothingValue += (throttle * (40 / 1000.f));
1100 throttleSmoothingValue = std::max(
static_cast<float>(-1.f), std::min(throttleSmoothingValue,
static_cast<float>(1.f)));
1101 throttle = throttleSmoothingValue;
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)));
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));
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);
1127 throttle = std::max(0.0f, throttle);
1130 throttle = (throttle + 1.0f) / 2.0f;
1133 if (additionalAxesFunctionIsManualControl) {
1134 qCDebug(JoystickVerboseLog)
1137 <<
"pitch:" << -pitch
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;
1150 qCDebug(JoystickVerboseLog)
1153 <<
"pitch:" << -pitch
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];
1169 quint64 buttonPressedBits = 0;
1170 for (
int buttonIndex = 0; buttonIndex < _totalButtonCount; buttonIndex++) {
1171 const quint64 buttonBit =
static_cast<quint64
>(1LL << buttonIndex);
1173 buttonPressedBits |= buttonBit;
1179 const uint16_t lowButtons =
static_cast<uint16_t
>(buttonPressedBits & 0xFFFF);
1180 const uint16_t highButtons =
static_cast<uint16_t
>((buttonPressedBits >> 16) & 0xFFFF);
1183 vehicle->
sendJoystickDataThreadSafe(roll, pitch, yaw, throttle, lowButtons, highButtons, pitchExtension, rollExtension, auxManualControl1, auxManualControl2, auxManualControl3, auxManualControl4, auxManualControl5, auxManualControl6);
1188void Joystick::_startPollingForActiveVehicle()
1191 if (!activeVehicle) {
1192 qCWarning(JoystickLog) <<
"Internal Error: No active vehicle to poll for";
1195 _startPollingForVehicle(*activeVehicle);
1198void Joystick::_startPollingForVehicle(
Vehicle &vehicle)
1200 qCDebug(JoystickLog) <<
"Starting joystick polling for vehicle. Vehicle id:" << vehicle.
id() <<
"Current flags:" << _pollingFlagsToString(_pollingFlags);
1202 if (_pollingFlags.testFlag(PollingForVehicle)) {
1203 qCWarning(JoystickLog) <<
"Internal Error: Joystick already polling for vehicle!";
1207 _pollingVehicle = &vehicle;
1208 qCDebug(JoystickLog) <<
"Started joystick polling for vehicle. Vehicle id:" << _pollingVehicle->
id();
1210 _buildAvailableButtonsActionList(_pollingVehicle);
1232 _pollingFlags |= PollingForVehicle;
1233 _startPollingThread();
1236void Joystick::_startPollingForConfiguration()
1238 qCDebug(JoystickLog) <<
"Starting joystick polling for configuration. Current flags:" << _pollingFlagsToString(_pollingFlags);
1240 if (_pollingFlags.testFlag(PollingForConfiguration)) {
1241 qCWarning(JoystickLog) <<
"Internal Error: Joystick already polling for configuration!";
1245 _pollingFlags |= PollingForConfiguration;
1246 _startPollingThread();
1249void Joystick::_stopPollingForConfiguration()
1251 qCDebug(JoystickLog) <<
"Stopping joystick polling for configuration. Current flags:" << _pollingFlagsToString(_pollingFlags);
1253 if (!_pollingFlags.testFlag(PollingForConfiguration)) {
1254 qCWarning(JoystickLog) <<
"Internal Error: Joystick not polling for configuration!";
1259 qCWarning(JoystickLog) <<
"Internal Error: Joystick polling thread not running!";
1262 const PollingFlags remainingFlags = _pollingFlags & ~PollingFlags(PollingForConfiguration);
1267 if (remainingFlags == PollingNone) {
1268 _stopPollingThread();
1271 _pollingFlags = remainingFlags;
1272 qCDebug(JoystickLog) <<
"Remaining flags:" << _pollingFlagsToString(_pollingFlags);
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();
1280void Joystick::_stopAllPollingForVehicle()
1282 qCDebug(JoystickLog) <<
"Stopping all joystick polling for vehicle. Current flags:" << _pollingFlagsToString(_pollingFlags);
1284 if (_pollingVehicle) {
1286 (void) disconnect(
this,
nullptr, _pollingVehicle,
nullptr);
1289 (void) disconnect(
this,
nullptr, gimbal,
nullptr);
1292 qCWarning(JoystickLog) <<
"Joystick polling thread not running even though _pollingVehicle was set.";
1296 const PollingFlags remainingFlags = _pollingFlags & ~PollingFlags(PollingForVehicle);
1301 if (remainingFlags == PollingNone) {
1302 _stopPollingThread();
1308 _pollingVehicle =
nullptr;
1309 _pollingFlags = remainingFlags;
1310 qCDebug(JoystickLog) <<
"Remaining flags:" << _pollingFlagsToString(_pollingFlags);
1312 if (remainingFlags.testFlag(PollingForConfiguration) && !isRunning()) {
1313 qCWarning(JoystickLog) <<
"Joystick polling thread not running but configuration polling flag set. Forcing start.";
1314 _startPollingThread();
1318void Joystick::_startPollingThread()
1321 qCDebug(JoystickLog) <<
"Polling thread already running. Flags:" << _pollingFlagsToString(_pollingFlags);
1323 qCDebug(JoystickLog) <<
"Starting polling thread. Flags:" << _pollingFlagsToString(_pollingFlags);
1324 _exitPollingThread =
false;
1329void Joystick::_stopPollingThread()
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";
1341 qCDebug(JoystickLog) <<
"Polling thread already stopped. Flags:" << _pollingFlagsToString(_pollingFlags);
1345QString Joystick::_pollingFlagsToString(PollingFlags flags)
const
1347 if (flags == PollingNone) {
1348 return QStringLiteral(
"None");
1351 if (flags.testFlag(PollingForVehicle)) {
1352 parts << QStringLiteral(
"PollingForVehicle");
1354 if (flags.testFlag(PollingForConfiguration)) {
1355 parts << QStringLiteral(
"PollingForConfiguration");
1357 return parts.join(QStringLiteral(
"|"));
1362 if (!_validAxis(axis)) {
1366 _rgCalibration[axis] = calibration;
1371 if (!_validAxis(axis)) {
1375 return _rgCalibration[axis];
1378void Joystick::_setJoystickAxisForAxisFunction(AxisFunction_t axisFunction,
int joystickAxis)
1381 qCWarning(JoystickLog) <<
"Internal Error: maxAxisFunction passed to _setJoystickAxisForAxisFunction";
1384 if (joystickAxis == kJoystickAxisNotAssigned) {
1385 qCWarning(JoystickLog) <<
"Internal Error: kJoystickAxisNotAssigned passed to _setJoystickAxisForAxisFunction";
1389 if (!_validAxis(joystickAxis)) {
1393 _axisFunctionToJoystickAxisMap[axisFunction] = joystickAxis;
1396int Joystick::_getJoystickAxisForAxisFunction(AxisFunction_t axisFunction)
const
1399 qCWarning(JoystickLog) <<
"Internal Error: maxAxisFunction passed to _getJoystickAxisForAxisFunction";
1400 return kJoystickAxisNotAssigned;
1403 return _axisFunctionToJoystickAxisMap.value(axisFunction, kJoystickAxisNotAssigned);
1408 switch (axisFunction) {
1441 switch (stickFunction) {
1484 if (!_validButton(button) || !_assignedButtonActions[button]) {
1488 _assignedButtonActions[button]->repeat = repeat;
1489 _assignedButtonActions[button]->buttonElapsedTimer.start();
1493 settings.beginGroup(QString::fromLatin1(kButtonActionArrayGroup));
1494 settings.beginGroup(QString::number(button));
1495 const QString repeatKey = QString::fromLatin1(kButtonRepeatKey);
1496 settings.setValue(repeatKey, repeat);
1504 if (!_validButton(button) || !_assignedButtonActions[button]) {
1508 return _assignedButtonActions[button]->repeat;
1513 if (!_validButton(button)) {
1517 qCDebug(JoystickLog) <<
"button:actionName" << button << actionName;
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);
1526 if (actionName.isEmpty() || actionName == _buttonActionNone) {
1527 if (_assignedButtonActions[button]) {
1528 delete _assignedButtonActions[button];
1529 _assignedButtonActions[button] =
nullptr;
1531 settings.setValue(actionNameKey, _buttonActionNone);
1532 settings.setValue(repeatKey,
false);
1534 if (!_assignedButtonActions[button]) {
1537 _assignedButtonActions[button]->actionName = actionName;
1539 const int idx = _findAvailableButtonActionIndex(actionName);
1541 const AvailableButtonAction *
const buttonAction = qobject_cast<const AvailableButtonAction*>(_availableButtonActions->
get(idx));
1543 _assignedButtonActions[button]->repeat =
false;
1548 settings.setValue(actionNameKey, _assignedButtonActions[button]->actionName);
1549 settings.setValue(repeatKey, _assignedButtonActions[button]->repeat);
1561 if (_validButton(button)) {
1562 if (_assignedButtonActions[button]) {
1563 return _assignedButtonActions[button]->actionName;
1567 return QString(_buttonActionNone);
1574 list.reserve(_totalButtonCount);
1576 for (
int button = 0; button < _totalButtonCount; button++) {
1577 if (_assignedButtonActions[button]) {
1578 list << _assignedButtonActions[button]->actionName;
1580 list << _buttonActionNone;
1587void Joystick::_executeButtonAction(
const QString &action,
const ButtonEvent_t buttonEvent)
1589 Vehicle *
const vehicle = _pollingVehicle;
1591 qCWarning(JoystickLog) <<
"Internal Error: No vehicle for joystick!";
1595 qCWarning(JoystickLog) <<
"Internal Error: Joystick not enabled for vehicle!";
1598 if (action == _buttonActionNone) {
1602 const int idx = _findAvailableButtonActionIndex(action);
1604 const AvailableButtonAction *
const availAction = qobject_cast<const AvailableButtonAction*>(_availableButtonActions->
get(idx));
1605 std::function<void()> handler;
1606 switch (buttonEvent) {
1608 handler = availAction->
onDown();
1614 handler = availAction->
onUp();
1620 qCDebug(JoystickLog) <<
"Button Action:" << action << buttonEvent;
1636 qCDebug(JoystickLog) <<
"Button Action: Switching flight mode to" << action;
1643 for (
int i = 0; i < _mavlinkActionManager->
actions()->count(); i++) {
1645 if (action == mavlinkAction->
label()) {
1646 qCDebug(JoystickLog) <<
"Button Action: Sending MAVLink action" << action;
1647 mavlinkAction->
sendTo(vehicle);
1653bool Joystick::_validAxis(
int axis)
const
1659 qCWarning(JoystickLog) <<
"Invalid axis index" << axis;
1663bool Joystick::_validButton(
int button)
const
1665 if ((button >= 0) && (button < _totalButtonCount)) {
1669 qCWarning(JoystickLog) <<
"Invalid button index" << button;
1673int Joystick::_findAvailableButtonActionIndex(
const QString &action)
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) {
1685void Joystick::_buildAvailableButtonsActionList(
Vehicle *vehicle)
1687 if (_availableButtonActions->
count()) {
1690 _availableActionTitles.clear();
1694 [
this]() { emit
setArmed(
true); }));
1696 [
this]() { emit
setArmed(
false); }));
1701 for (
const QString &mode : list) {
1784#ifndef QGC_NO_ARDUPILOT_DIALECT
1792 for (
const auto &action : customActions) {
1796 std::function<void()> repeatFn = action.canRepeat ? std::function<void()>([]{}) : nullptr;
1800 for (
int i = 0; i < _mavlinkActionManager->
actions()->count(); i++) {
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();
1817 return QStringLiteral(
"Roll");
1819 return QStringLiteral(
"Pitch");
1821 return QStringLiteral(
"Yaw");
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");
1841 return QStringLiteral(
"Unassigned");
1848 _startPollingForConfiguration();
1853 _stopPollingForConfiguration();
1858 if (!_validAxis(joystickAxis)) {
1864 if (_axisFunctionToJoystickAxisMap.value(axisFunction, kJoystickAxisNotAssigned) == joystickAxis) {
1865 return axisFunction;
1874 _exitPollingThread =
true;
1876 if (QThread::currentThread() ==
this) {
1877 qCWarning(JoystickLog) <<
"Skipping wait() on joystick thread";
1886 if (_linkedGroupId != groupId) {
1887 _linkedGroupId = groupId;
1891 settings.beginGroup(QStringLiteral(
"Joystick"));
1893 if (groupId.isEmpty()) {
1894 settings.remove(QStringLiteral(
"LinkedGroupId"));
1896 settings.setValue(QStringLiteral(
"LinkedGroupId"), groupId);
1907 if (_linkedGroupRole != role) {
1908 _linkedGroupRole = role;
1912 settings.beginGroup(QStringLiteral(
"Joystick"));
1914 if (role.isEmpty()) {
1915 settings.remove(QStringLiteral(
"LinkedGroupRole"));
1917 settings.setValue(QStringLiteral(
"LinkedGroupRole"), role);
#define QGC_LOGGING_CATEGORY(name, categoryStr)
A Fact is used to hold a single value within the system.
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)
Q_INVOKABLE void stopConfiguration()
Tells the joystick that the configuration UI is being closed so it can do any special processing requ...
void rawButtonPressedChanged(int index, bool pressed)
Signalled during PollingForConfiguration.
void gimbalYawLock(bool lock)
@ additionalAxis2Function
@ additionalAxis6Function
@ additionalAxis3Function
@ additionalAxis4Function
@ additionalAxis1Function
@ additionalAxis5Function
Joystick(const QString &name, int axisCount, int buttonCount, int hatCount, QObject *parent=nullptr)
void stopContinuousFocus()
RemoteControlCalibrationController::StickFunction mapAxisFunctionToRCCStickFunction(AxisFunction_t axisFunction) const
void setLinkedGroupRole(const QString &role)
void setFlightMode(const QString &flightMode)
void motorInterlock(bool enable)
static QString axisFunctionToString(AxisFunction_t function)
void setFunctionForChannel(RemoteControlCalibrationController::StickFunction stickFunction, int channel)
void axisValues(float roll, float pitch, float yaw, float throttle)
void buttonActionsChanged()
@ ButtonEventDownTransition
@ ButtonEventUpTransition
void assignableActionsChanged()
void unknownAction(const QString &action)
int getChannelForFunction(RemoteControlCalibrationController::StickFunction stickFunction) const
Q_INVOKABLE QString getButtonAction(int button) const
void stepZoom(int direction)
QStringList buttonActions() const
AxisFunction_t mapRCCStickFunctionToAxisFunction(RemoteControlCalibrationController::StickFunction stickFunction) const
Q_INVOKABLE void startConfiguration()
Tells the joystick that the configuration UI is being displayed so it can do any special processing r...
Joystick::AxisCalibration_t getAxisCalibration(int axis) const
void setAxisCalibration(int axis, const AxisCalibration_t &calibration)
void startContinuousZoom(int direction)
JoystickSettings * settings()
void stopContinuousZoom()
Q_INVOKABLE bool getButtonRepeat(int button)
Q_INVOKABLE void setButtonAction(int button, const QString &action)
void stepCamera(int direction)
void setVtolInFwdFlight(bool set)
void gripperAction(GRIPPER_ACTIONS gripperAction)
void stepStream(int direction)
void landingGearRetract()
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)
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.
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 ...
@ stickFunctionAdditionalAxis6
@ stickFunctionRollExtension
@ stickFunctionAdditionalAxis1
@ stickFunctionAdditionalAxis4
@ stickFunctionAdditionalAxis2
@ stickFunctionAdditionalAxis3
@ stickFunctionAdditionalAxis5
@ stickFunctionPitchExtension
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.
Q_INVOKABLE void sendGripperAction(GRIPPER_ACTIONS gripperOption)
void sendJoystickAuxRcOverrideThreadSafe(const std::array< uint16_t, kAuxRcOverrideChannelCount > &channelValues, const std::array< bool, kAuxRcOverrideChannelCount > &channelEnabled, bool useRcOverride)
Q_INVOKABLE void emergencyStop()
Command vehicle to kill all motors no matter what state.
void setFlightMode(const QString &flightMode)
Q_INVOKABLE void landingGearDeploy()
Command vichecle to deploy landing gear.
void flightModesChanged()
GimbalController * gimbalController()
void setVtolInFwdFlight(bool vtolInFwdFlight)
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)
Q_INVOKABLE void landingGearRetract()
Command vichecle to retract landing gear.
VehicleSupports * supports()
QStringList flightModes()
void setArmedShowError(bool armed)