5#include <QtCore/QObject>
6#include <QtCore/QThread>
7#include <QtCore/QVariantMap>
8#include <QtGui/QVector3D>
9#include <QtQmlIntegration/QtQmlIntegration>
41 std::function<
void()>
onDown,
42 std::function<
void()>
onUp =
nullptr,
43 std::function<
void()>
onRepeat =
nullptr,
44 QObject *parent =
nullptr);
46 const QString &
action()
const {
return _actionName; }
48 const std::function<void()> &
onDown()
const {
return _onDown; }
49 const std::function<void()> &
onRepeat()
const {
return _onRepeat; }
50 const std::function<void()> &
onUp()
const {
return _onUp; }
53 const QString _actionName;
54 const std::function<void()> _onDown;
55 const std::function<void()> _onRepeat;
56 const std::function<void()> _onUp;
67 Q_MOC_INCLUDE(
"QmlObjectListModel.h")
68 Q_MOC_INCLUDE(
"Vehicle.h")
72#ifdef QGC_UNITTEST_BUILD
73 friend class JoystickTest;
77 Q_PROPERTY(QString
name READ
name CONSTANT)
85 Q_PROPERTY(QString
guid READ
guid CONSTANT)
95 Q_PROPERTY(QString
path READ
path CONSTANT)
211 virtual bool hasLED()
const {
return false; }
212 virtual QString
guid()
const {
return QString(); }
215 virtual QString
serial()
const {
return QString(); }
223 virtual QString
path()
const {
return QString(); }
229 Q_INVOKABLE
virtual void rumble(quint16 lowFreq, quint16 highFreq, quint32 durationMs) { Q_UNUSED(lowFreq); Q_UNUSED(highFreq); Q_UNUSED(durationMs); }
230 Q_INVOKABLE
virtual void rumbleTriggers(quint16 left, quint16 right, quint32 durationMs) { Q_UNUSED(left); Q_UNUSED(right); Q_UNUSED(durationMs); }
231 Q_INVOKABLE
virtual void setLED(quint8 red, quint8 green, quint8 blue) { Q_UNUSED(red); Q_UNUSED(green); Q_UNUSED(blue); }
232 Q_INVOKABLE
virtual QString
axisLabel(
int axis)
const { Q_UNUSED(axis);
return QString(); }
233 Q_INVOKABLE
virtual QString
buttonLabel(
int button)
const { Q_UNUSED(button);
return QString(); }
234 Q_INVOKABLE
virtual QString
getMapping()
const {
return QString(); }
235 Q_INVOKABLE
virtual bool addMapping(
const QString &mapping) { Q_UNUSED(mapping);
return false; }
251 Q_UNUSED(touchpad); Q_UNUSED(finger);
return QVariantMap();
255 Q_INVOKABLE
virtual QVariantMap
getBall(
int ball)
const { Q_UNUSED(ball);
return QVariantMap(); }
258 Q_INVOKABLE
virtual bool sendEffect(
const QByteArray &data) { Q_UNUSED(data);
return false; }
261 Q_INVOKABLE
virtual QVariantMap
getAxisBinding(
int axis)
const { Q_UNUSED(axis);
return QVariantMap(); }
262 Q_INVOKABLE
virtual QVariantMap
getButtonBinding(
int button)
const { Q_UNUSED(button);
return QVariantMap(); }
265 Q_INVOKABLE
virtual bool hasButton(
int button)
const { Q_UNUSED(button);
return false; }
266 Q_INVOKABLE
virtual bool hasAxis(
int axis)
const { Q_UNUSED(axis);
return false; }
272 Q_INVOKABLE
virtual QString
buttonLabelForType(
int button)
const { Q_UNUSED(button);
return QString(); }
275 Q_INVOKABLE
virtual bool hasHaptic()
const {
return false; }
279 Q_INVOKABLE
virtual bool hapticRumblePlay(
float strength, quint32 durationMs) { Q_UNUSED(strength); Q_UNUSED(durationMs);
return false; }
286 Q_INVOKABLE
virtual bool setVirtualAxis(
int axis,
int value) { Q_UNUSED(axis); Q_UNUSED(value);
return false; }
287 Q_INVOKABLE
virtual bool setVirtualButton(
int button,
bool down) { Q_UNUSED(button); Q_UNUSED(down);
return false; }
288 Q_INVOKABLE
virtual bool setVirtualHat(
int hat, quint8 value) { Q_UNUSED(hat); Q_UNUSED(value);
return false; }
289 Q_INVOKABLE
virtual bool setVirtualBall(
int ball,
int dx,
int dy) { Q_UNUSED(ball); Q_UNUSED(dx); Q_UNUSED(dy);
return false; }
290 Q_INVOKABLE
virtual bool setVirtualTouchpad(
int touchpad,
int finger,
bool down,
float x,
float y,
float pressure) {
291 Q_UNUSED(touchpad); Q_UNUSED(finger); Q_UNUSED(down); Q_UNUSED(x); Q_UNUSED(y); Q_UNUSED(pressure);
return false;
294 Q_UNUSED(sensorType); Q_UNUSED(x); Q_UNUSED(y); Q_UNUSED(z);
return false;
298 Q_INVOKABLE
virtual bool hasMonoLED()
const {
return false; }
299 Q_INVOKABLE
virtual bool hasRGBLED()
const {
return false; }
306 Q_INVOKABLE
virtual QVariantMap
getAxisInitialState(
int axis)
const { Q_UNUSED(axis);
return QVariantMap(); }
309 Q_INVOKABLE
virtual bool setMapping(
const QString &mapping) { Q_UNUSED(mapping);
return false; }
344 void axisValues(
float roll,
float pitch,
float yaw,
float throttle);
372 void vehicleJoystickData(
float roll,
float pitch,
float yaw,
float throttle, uint16_t buttonsLow, uint16_t buttonsHigh,
float gimbalPitch,
float gimbalYaw);
379 void touchpadEvent(
int touchpad,
int finger,
bool down,
float x,
float y,
float pressure);
392 void _flightModesChanged() { _buildAvailableButtonsActionList(_pollingVehicle); }
397 PollingForVehicle = 0x1,
398 PollingForConfiguration = 0x2,
400 using PollingFlags = QFlags<PollingFlag>;
402 using AxisFunctionMap_t = QMap<AxisFunction_t, int>;
404 virtual bool _open() = 0;
405 virtual void _close() = 0;
406 virtual bool _update() = 0;
408 virtual bool _getButton(
int i)
const = 0;
409 virtual int _getAxisValue(
int axis)
const = 0;
410 virtual bool _getHat(
int hat,
int i)
const = 0;
414 void _startPollingForVehicle(
Vehicle &vehicle);
415 void _startPollingForActiveVehicle();
416 void _startPollingForConfiguration();
417 void _stopPollingForConfiguration();
418 void _stopAllPollingForVehicle();
419 void _startPollingThread();
420 void _stopPollingThread();
421 QString _pollingFlagsToString(PollingFlags flags)
const;
422 PollingFlags _pollingFlags = PollingNone;
424 Vehicle* _pollingVehicle =
nullptr;
426 void _resetFunctionToAxisMap();
427 void _resetAxisCalibrationData();
428 void _resetButtonActionData();
429 void _resetButtonEventStates();
431 void _foundInvalidAxisSettingsCleanup();
433 void _loadButtonSettings();
434 void _loadAxisSettings(
bool joystickCalibrated,
int transmitterMode);
435 void _saveButtonSettings();
436 void _saveAxisSettings(
int transmitterMode);
437 void _loadFromSettingsIntoCalibrationData();
438 void _saveFromCalibrationDataIntoSettings();
439 void _clearAxisSettings();
440 void _clearButtonSettings();
443 float _adjustRange(
int reversedAxisValue,
const AxisCalibration_t &calibration,
bool withDeadbands);
444 uint16_t _adjustRangeToRcOverridePwm(
int value,
const AxisCalibration_t &calibration,
bool withDeadbands);
446 void _executeButtonAction(
const QString &action,
const ButtonEvent_t buttonEvent);
447 int _findAvailableButtonActionIndex(
const QString &action);
448 bool _validAxis(
int axis)
const;
449 bool _validButton(
int button)
const;
451 void _handleButtons();
452 void _buildAvailableButtonsActionList(
Vehicle *vehicle);
453 AxisFunction_t _getAxisFunctionForJoystickAxis(
int joystickAxis)
const;
454 int _getJoystickAxisForAxisFunction(
AxisFunction_t axisFunction)
const;
455 void _setJoystickAxisForAxisFunction(
AxisFunction_t axisFunction,
int axis);
456 void _updateButtonEventState(
int buttonIndex,
const bool buttonPressed,
ButtonEvent_t &buttonEventState);
457 void _updateButtonEventStates(QVector<ButtonEvent_t> &buttonEventStates);
460 void _remapFunctionsInFunctionMapToNewTransmittedMode(
int fromMode,
int toMode);
462 int _hatButtonCount = 0;
463 int _totalButtonCount = 0;
464 QVector<AxisCalibration_t> _rgCalibration;
465 QVector<ButtonEvent_t> _buttonEventStates;
466 QVector<AssignedButtonAction*> _assignedButtonActions;
473 AxisFunctionMap_t _axisFunctionToJoystickAxisMap;
474 static constexpr const int kJoystickAxisNotAssigned = -1;
476 QElapsedTimer _axisElapsedTimer;
477 QStringList _availableActionTitles;
478 std::atomic<bool> _exitPollingThread =
false;
481 QString _linkedGroupId;
482 QString _linkedGroupRole;
484 static constexpr const char *_buttonActionNone = QT_TR_NOOP(
"No Action");
485 static constexpr const char *_buttonActionArm = QT_TR_NOOP(
"Arm");
486 static constexpr const char *_buttonActionDisarm = QT_TR_NOOP(
"Disarm");
487 static constexpr const char *_buttonActionToggleArm = QT_TR_NOOP(
"Toggle Arm");
488 static constexpr const char *_buttonActionVTOLFixedWing = QT_TR_NOOP(
"VTOL: Fixed Wing");
489 static constexpr const char *_buttonActionVTOLMultiRotor = QT_TR_NOOP(
"VTOL: Multi-Rotor");
490 static constexpr const char *_buttonActionContinuousZoomIn = QT_TR_NOOP(
"Continuous Zoom In");
491 static constexpr const char *_buttonActionContinuousZoomOut = QT_TR_NOOP(
"Continuous Zoom Out");
492 static constexpr const char *_buttonActionStepZoomIn = QT_TR_NOOP(
"Step Zoom In");
493 static constexpr const char *_buttonActionStepZoomOut = QT_TR_NOOP(
"Step Zoom Out");
494 static constexpr const char *_buttonActionContinuousFocusIn = QT_TR_NOOP(
"Continuous Focus In");
495 static constexpr const char *_buttonActionContinuousFocusOut = QT_TR_NOOP(
"Continuous Focus Out");
496 static constexpr const char *_buttonActionStepFocusIn = QT_TR_NOOP(
"Step Focus In");
497 static constexpr const char *_buttonActionStepFocusOut = QT_TR_NOOP(
"Step Focus Out");
498 static constexpr const char *_buttonActionNextStream = QT_TR_NOOP(
"Next Video Stream");
499 static constexpr const char *_buttonActionPreviousStream = QT_TR_NOOP(
"Previous Video Stream");
500 static constexpr const char *_buttonActionNextCamera = QT_TR_NOOP(
"Next Camera");
501 static constexpr const char *_buttonActionPreviousCamera = QT_TR_NOOP(
"Previous Camera");
502 static constexpr const char *_buttonActionTriggerCamera = QT_TR_NOOP(
"Trigger Camera");
503 static constexpr const char *_buttonActionStartVideoRecord = QT_TR_NOOP(
"Start Recording Video");
504 static constexpr const char *_buttonActionStopVideoRecord = QT_TR_NOOP(
"Stop Recording Video");
505 static constexpr const char *_buttonActionToggleVideoRecord = QT_TR_NOOP(
"Toggle Recording Video");
506 static constexpr const char *_buttonActionGimbalDown = QT_TR_NOOP(
"Gimbal Down");
507 static constexpr const char *_buttonActionGimbalUp = QT_TR_NOOP(
"Gimbal Up");
508 static constexpr const char *_buttonActionGimbalLeft = QT_TR_NOOP(
"Gimbal Left");
509 static constexpr const char *_buttonActionGimbalRight = QT_TR_NOOP(
"Gimbal Right");
510 static constexpr const char *_buttonActionGimbalCenter = QT_TR_NOOP(
"Gimbal Center");
511 static constexpr const char *_buttonActionGimbalYawLock = QT_TR_NOOP(
"Gimbal Yaw Lock");
512 static constexpr const char *_buttonActionGimbalYawFollow = QT_TR_NOOP(
"Gimbal Yaw Follow");
513 static constexpr const char *_buttonActionEmergencyStop = QT_TR_NOOP(
"Emergency Stop");
514 static constexpr const char *_buttonActionGripperGrab = QT_TR_NOOP(
"Gripper Grab");
515 static constexpr const char *_buttonActionGripperRelease = QT_TR_NOOP(
"Gripper Release");
516 static constexpr const char *_buttonActionGripperHold = QT_TR_NOOP(
"Gripper Hold");
517 static constexpr const char *_buttonActionLandingGearDeploy= QT_TR_NOOP(
"Landing gear deploy");
518 static constexpr const char *_buttonActionLandingGearRetract= QT_TR_NOOP(
"Landing gear retract");
519 static constexpr const char *_buttonActionMotorInterlockEnable= QT_TR_NOOP(
"Motor Interlock enable");
520 static constexpr const char *_buttonActionMotorInterlockDisable= QT_TR_NOOP(
"Motor Interlock disable");
virtual void setPlayerIndex(int index)
virtual Q_INVOKABLE QString getMappingForGUID(const QString &guid) const
void setLinkedGroupId(const QString &groupId)
virtual Q_INVOKABLE bool hasGyroscope() const
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.
virtual Q_INVOKABLE bool setAccelerometerEnabled(bool enabled)
virtual Q_INVOKABLE QVariantMap getButtonBinding(int button) const
virtual Q_INVOKABLE void setLED(quint8 red, quint8 green, quint8 blue)
virtual Q_INVOKABLE bool setMapping(const QString &mapping)
virtual Q_INVOKABLE bool setGyroscopeEnabled(bool enabled)
void gimbalYawLock(bool lock)
virtual bool hasRumbleTriggers() const
void touchpadEvent(int touchpad, int finger, bool down, float x, float y, float pressure)
virtual quint16 firmwareVersion() const
virtual int batteryPercent() const
virtual bool requiresCalibration() const
QString linkedGroupId() const
HOTAS/Multi-device linking (devices with same groupId act as single joystick)
virtual int ballCount() const
virtual Q_INVOKABLE QString realGamepadType() const
virtual Q_INVOKABLE void hapticRumbleStop()
virtual Q_INVOKABLE float gyroscopeDataRate() const
virtual Q_INVOKABLE bool setVirtualButton(int button, bool down)
virtual Q_INVOKABLE QString connectionState() const
virtual Q_INVOKABLE bool setVirtualAxis(int axis, int value)
@ additionalAxis2Function
@ additionalAxis6Function
@ additionalAxis3Function
@ additionalAxis4Function
@ additionalAxis1Function
@ additionalAxis5Function
QString disabledActionName() const
virtual Q_INVOKABLE bool hasRGBLED() const
void batteryStateChanged()
void stopContinuousFocus()
virtual Q_INVOKABLE void rumble(quint16 lowFreq, quint16 highFreq, quint32 durationMs)
virtual QString deviceType() const
virtual Q_INVOKABLE bool sendEffect(const QByteArray &data)
virtual bool isVirtual() const
virtual Q_INVOKABLE bool setVirtualTouchpad(int touchpad, int finger, bool down, float x, float y, float pressure)
RemoteControlCalibrationController::StickFunction mapAxisFunctionToRCCStickFunction(AxisFunction_t axisFunction) const
virtual bool isGamepad() const
HatDirection
Standard gamepad hat/D-pad directions.
const QmlObjectListModel * assignableActions() const
virtual QString gamepadType() const
void setLinkedGroupRole(const QString &role)
void setFlightMode(const QString &flightMode)
virtual Q_INVOKABLE bool hapticRumblePlay(float strength, quint32 durationMs)
void motorInterlock(bool enable)
virtual Q_INVOKABLE QString buttonLabel(int button) const
static QString axisFunctionToString(AxisFunction_t function)
void setFunctionForChannel(RemoteControlCalibrationController::StickFunction stickFunction, int channel)
virtual Q_INVOKABLE void rumbleTriggers(quint16 left, quint16 right, quint32 durationMs)
virtual Q_INVOKABLE bool setVirtualHat(int hat, quint8 value)
void axisValues(float roll, float pitch, float yaw, float throttle)
virtual Q_INVOKABLE QString axisLabel(int axis) const
void buttonActionsChanged()
virtual Q_INVOKABLE bool hasButton(int button) const
@ ButtonEventDownTransition
@ ButtonEventUpTransition
void assignableActionsChanged()
virtual Q_INVOKABLE bool hasAccelerometer() const
static constexpr int AxisMin
virtual Q_INVOKABLE QVector3D accelerometerData() const
void unknownAction(const QString &action)
void playerIndexChanged()
virtual quint16 vendorId() const
virtual Q_INVOKABLE QString getMapping() const
int getChannelForFunction(RemoteControlCalibrationController::StickFunction stickFunction) const
void vehicleJoystickData(float roll, float pitch, float yaw, float throttle, uint16_t buttonsLow, uint16_t buttonsHigh, float gimbalPitch, float gimbalYaw)
virtual Q_INVOKABLE QVariantMap getAxisBinding(int axis) const
virtual int playerIndex() const
Q_INVOKABLE QString getButtonAction(int button) const
virtual QString serial() const
void connectionStateChanged(const QString &newState)
void stepZoom(int direction)
QStringList buttonActions() const
AxisFunction_t mapRCCStickFunctionToAxisFunction(RemoteControlCalibrationController::StickFunction stickFunction) const
virtual Q_INVOKABLE bool hasMonoLED() const
Q_INVOKABLE void startConfiguration()
Tells the joystick that the configuration UI is being displayed so it can do any special processing r...
virtual QString connectionType() const
virtual quint16 productId() const
Joystick::AxisCalibration_t getAxisCalibration(int axis) const
virtual bool hasRumble() const
void setAxisCalibration(int axis, const AxisCalibration_t &calibration)
virtual Q_INVOKABLE bool setVirtualBall(int ball, int dx, int dy)
virtual Q_INVOKABLE QVariantMap getBall(int ball) const
QString buttonActionNone() const
void startContinuousZoom(int direction)
virtual Q_INVOKABLE bool hapticRumbleInit()
JoystickSettings * settings()
void stopContinuousZoom()
virtual Q_INVOKABLE int hapticEffectsCount() const
virtual Q_INVOKABLE bool hasPlayerLED() const
GamepadAxis
Standard gamepad axis indices.
Q_INVOKABLE bool getButtonRepeat(int button)
virtual bool hasLED() const
static constexpr int AxisMax
Q_INVOKABLE void setButtonAction(int button, const QString &action)
void stepCamera(int direction)
virtual Q_INVOKABLE int touchpadFingerCount(int touchpad) const
void accelerometerDataUpdated(const QVector3D &data)
virtual Q_INVOKABLE bool addMapping(const QString &mapping)
virtual Q_INVOKABLE bool sendVirtualSensorData(int sensorType, float x, float y, float z)
void setVtolInFwdFlight(bool set)
void gripperAction(GRIPPER_ACTIONS gripperAction)
void stepStream(int direction)
virtual Q_INVOKABLE bool hapticRumbleSupported() const
virtual Q_INVOKABLE QVector3D gyroscopeData() const
void landingGearRetract()
virtual Q_INVOKABLE bool hasAxis(int axis) const
GamepadButton
Standard gamepad button indices.
void stepFocus(int direction)
virtual QString path() const
void gimbalPitchStart(int direction)
virtual Q_INVOKABLE int touchpadCount() const
virtual Q_INVOKABLE float accelerometerDataRate() const
QStringList assignableActionTitles() const
virtual Q_INVOKABLE QVariantMap getTouchpadFinger(int touchpad, int finger) const
void gyroscopeDataUpdated(const QVector3D &data)
virtual QString guid() const
virtual Q_INVOKABLE QVariantMap getAxisInitialState(int axis) const
void linkedGroupChanged()
void rawChannelValuesChanged(QVector< int > channelValues)
Signalled during PollingForConfiguration.
QString linkedGroupRole() const
void startContinuousFocus(int direction)
void gimbalYawStart(int direction)
virtual Q_INVOKABLE QString buttonLabelForType(int button) const
Q_INVOKABLE void setButtonRepeat(int button, bool repeat)
virtual QString powerState() const
virtual Q_INVOKABLE bool hasHaptic() const
Loads the specified action file and provides access to the actions it contains.
StickFunction
These identify the various controls functions. They are also used as indices into the _rgFunctioInfo ...