5#include <QtCore/QLoggingCategory>
6#include <QtCore/QObject>
7#include <QtCore/QThread>
8#include <QtCore/QVariantMap>
9#include <QtGui/QVector3D>
10#include <QtQmlIntegration/QtQmlIntegration>
38 Q_PROPERTY(QString action READ action CONSTANT)
39 Q_PROPERTY(
bool canRepeat READ canRepeat CONSTANT)
44 const QString &action()
const {
return _actionName; }
45 bool canRepeat()
const {
return _repeat; }
48 const QString _actionName;
49 const bool _repeat =
false;
60 Q_MOC_INCLUDE(
"QmlObjectListModel.h")
61 Q_MOC_INCLUDE(
"Vehicle.h")
65#ifdef QGC_UNITTEST_BUILD
66 friend class JoystickTest;
204 virtual bool hasLED()
const {
return false; }
205 virtual QString
guid()
const {
return QString(); }
208 virtual QString
serial()
const {
return QString(); }
216 virtual QString
path()
const {
return QString(); }
222 Q_INVOKABLE
virtual void rumble(quint16 lowFreq, quint16 highFreq, quint32 durationMs) { Q_UNUSED(lowFreq); Q_UNUSED(highFreq); Q_UNUSED(durationMs); }
223 Q_INVOKABLE
virtual void rumbleTriggers(quint16 left, quint16 right, quint32 durationMs) { Q_UNUSED(left); Q_UNUSED(right); Q_UNUSED(durationMs); }
224 Q_INVOKABLE
virtual void setLED(quint8 red, quint8 green, quint8 blue) { Q_UNUSED(red); Q_UNUSED(green); Q_UNUSED(blue); }
225 Q_INVOKABLE
virtual QString
axisLabel(
int axis)
const { Q_UNUSED(axis);
return QString(); }
226 Q_INVOKABLE
virtual QString
buttonLabel(
int button)
const { Q_UNUSED(button);
return QString(); }
227 Q_INVOKABLE
virtual QString
getMapping()
const {
return QString(); }
228 Q_INVOKABLE
virtual bool addMapping(
const QString &mapping) { Q_UNUSED(mapping);
return false; }
244 Q_UNUSED(touchpad); Q_UNUSED(finger);
return QVariantMap();
248 Q_INVOKABLE
virtual QVariantMap
getBall(
int ball)
const { Q_UNUSED(ball);
return QVariantMap(); }
251 Q_INVOKABLE
virtual bool sendEffect(
const QByteArray &data) { Q_UNUSED(data);
return false; }
254 Q_INVOKABLE
virtual QVariantMap
getAxisBinding(
int axis)
const { Q_UNUSED(axis);
return QVariantMap(); }
255 Q_INVOKABLE
virtual QVariantMap
getButtonBinding(
int button)
const { Q_UNUSED(button);
return QVariantMap(); }
258 Q_INVOKABLE
virtual bool hasButton(
int button)
const { Q_UNUSED(button);
return false; }
259 Q_INVOKABLE
virtual bool hasAxis(
int axis)
const { Q_UNUSED(axis);
return false; }
265 Q_INVOKABLE
virtual QString
buttonLabelForType(
int button)
const { Q_UNUSED(button);
return QString(); }
268 Q_INVOKABLE
virtual bool hasHaptic()
const {
return false; }
272 Q_INVOKABLE
virtual bool hapticRumblePlay(
float strength, quint32 durationMs) { Q_UNUSED(strength); Q_UNUSED(durationMs);
return false; }
279 Q_INVOKABLE
virtual bool setVirtualAxis(
int axis,
int value) { Q_UNUSED(axis); Q_UNUSED(value);
return false; }
280 Q_INVOKABLE
virtual bool setVirtualButton(
int button,
bool down) { Q_UNUSED(button); Q_UNUSED(down);
return false; }
281 Q_INVOKABLE
virtual bool setVirtualHat(
int hat, quint8 value) { Q_UNUSED(hat); Q_UNUSED(value);
return false; }
282 Q_INVOKABLE
virtual bool setVirtualBall(
int ball,
int dx,
int dy) { Q_UNUSED(ball); Q_UNUSED(dx); Q_UNUSED(dy);
return false; }
283 Q_INVOKABLE
virtual bool setVirtualTouchpad(
int touchpad,
int finger,
bool down,
float x,
float y,
float pressure) {
284 Q_UNUSED(touchpad); Q_UNUSED(finger); Q_UNUSED(down); Q_UNUSED(x); Q_UNUSED(y); Q_UNUSED(pressure);
return false;
287 Q_UNUSED(sensorType); Q_UNUSED(x); Q_UNUSED(y); Q_UNUSED(z);
return false;
291 Q_INVOKABLE
virtual bool hasMonoLED()
const {
return false; }
292 Q_INVOKABLE
virtual bool hasRGBLED()
const {
return false; }
299 Q_INVOKABLE
virtual QVariantMap
getAxisInitialState(
int axis)
const { Q_UNUSED(axis);
return QVariantMap(); }
302 Q_INVOKABLE
virtual bool setMapping(
const QString &mapping) { Q_UNUSED(mapping);
return false; }
322 void setFunctionForChannel(RemoteControlCalibrationController::StickFunction stickFunction,
int channel);
337 void axisValues(
float roll,
float pitch,
float yaw,
float throttle);
362 void vehicleJoystickData(
float roll,
float pitch,
float yaw,
float throttle, uint16_t buttonsLow, uint16_t buttonsHigh,
float gimbalPitch,
float gimbalYaw);
369 void touchpadEvent(
int touchpad,
int finger,
bool down,
float x,
float y,
float pressure);
382 void _flightModesChanged() { _buildAvailableButtonsActionList(_pollingVehicle); }
387 PollingForConfiguration,
391 using AxisFunctionMap_t = QMap<AxisFunction_t, int>;
393 virtual bool _open() = 0;
394 virtual void _close() = 0;
395 virtual bool _update() = 0;
397 virtual bool _getButton(
int i)
const = 0;
398 virtual int _getAxisValue(
int axis)
const = 0;
399 virtual bool _getHat(
int hat,
int i)
const = 0;
403 void _startPollingForVehicle(
Vehicle &vehicle);
404 void _startPollingForActiveVehicle();
405 void _startPollingForConfiguration();
406 void _stopPollingForConfiguration();
407 void _stopAllPolling();
408 QString _pollingTypeToString(PollingType pollingType)
const;
409 PollingType _currentPollingType = NotPolling;
410 PollingType _previousPollingType = NotPolling;
411 Vehicle* _pollingVehicle =
nullptr;
413 void _resetFunctionToAxisMap();
414 void _resetAxisCalibrationData();
415 void _resetButtonActionData();
416 void _resetButtonEventStates();
418 void _foundInvalidAxisSettingsCleanup();
420 void _loadButtonSettings();
421 void _loadAxisSettings(
bool joystickCalibrated,
int transmitterMode);
422 void _saveButtonSettings();
423 void _saveAxisSettings(
int transmitterMode);
424 void _loadFromSettingsIntoCalibrationData();
425 void _saveFromCalibrationDataIntoSettings();
426 void _clearAxisSettings();
427 void _clearButtonSettings();
430 float _adjustRange(
int reversedAxisValue,
const AxisCalibration_t &calibration,
bool withDeadbands);
432 void _executeButtonAction(
const QString &action,
const ButtonEvent_t buttonEvent);
433 int _findAvailableButtonActionIndex(
const QString &action);
434 bool _validAxis(
int axis)
const;
435 bool _validButton(
int button)
const;
437 void _handleButtons();
438 void _buildAvailableButtonsActionList(
Vehicle *vehicle);
439 AxisFunction_t _getAxisFunctionForJoystickAxis(
int joystickAxis)
const;
440 int _getJoystickAxisForAxisFunction(
AxisFunction_t axisFunction)
const;
441 void _setJoystickAxisForAxisFunction(
AxisFunction_t axisFunction,
int axis);
442 void _updateButtonEventState(
int buttonIndex,
const bool buttonPressed,
ButtonEvent_t &buttonEventState);
443 void _updateButtonEventStates(QVector<ButtonEvent_t> &buttonEventStates);
446 void _remapFunctionsInFunctionMapToNewTransmittedMode(
int fromMode,
int toMode);
448 int _hatButtonCount = 0;
449 int _totalButtonCount = 0;
450 QVector<AxisCalibration_t> _rgCalibration;
451 QVector<ButtonEvent_t> _buttonEventStates;
452 QVector<AssignedButtonAction*> _assignedButtonActions;
459 AxisFunctionMap_t _axisFunctionToJoystickAxisMap;
460 static constexpr const int kJoystickAxisNotAssigned = -1;
462 QElapsedTimer _axisElapsedTimer;
463 QStringList _availableActionTitles;
464 std::atomic<bool> _exitThread =
false;
467 QString _linkedGroupId;
468 QString _linkedGroupRole;
470 static constexpr const char *_buttonActionNone = QT_TR_NOOP(
"No Action");
471 static constexpr const char *_buttonActionArm = QT_TR_NOOP(
"Arm");
472 static constexpr const char *_buttonActionDisarm = QT_TR_NOOP(
"Disarm");
473 static constexpr const char *_buttonActionToggleArm = QT_TR_NOOP(
"Toggle Arm");
474 static constexpr const char *_buttonActionVTOLFixedWing = QT_TR_NOOP(
"VTOL: Fixed Wing");
475 static constexpr const char *_buttonActionVTOLMultiRotor = QT_TR_NOOP(
"VTOL: Multi-Rotor");
476 static constexpr const char *_buttonActionContinuousZoomIn = QT_TR_NOOP(
"Continuous Zoom In");
477 static constexpr const char *_buttonActionContinuousZoomOut = QT_TR_NOOP(
"Continuous Zoom Out");
478 static constexpr const char *_buttonActionStepZoomIn = QT_TR_NOOP(
"Step Zoom In");
479 static constexpr const char *_buttonActionStepZoomOut = QT_TR_NOOP(
"Step Zoom Out");
480 static constexpr const char *_buttonActionNextStream = QT_TR_NOOP(
"Next Video Stream");
481 static constexpr const char *_buttonActionPreviousStream = QT_TR_NOOP(
"Previous Video Stream");
482 static constexpr const char *_buttonActionNextCamera = QT_TR_NOOP(
"Next Camera");
483 static constexpr const char *_buttonActionPreviousCamera = QT_TR_NOOP(
"Previous Camera");
484 static constexpr const char *_buttonActionTriggerCamera = QT_TR_NOOP(
"Trigger Camera");
485 static constexpr const char *_buttonActionStartVideoRecord = QT_TR_NOOP(
"Start Recording Video");
486 static constexpr const char *_buttonActionStopVideoRecord = QT_TR_NOOP(
"Stop Recording Video");
487 static constexpr const char *_buttonActionToggleVideoRecord = QT_TR_NOOP(
"Toggle Recording Video");
488 static constexpr const char *_buttonActionGimbalDown = QT_TR_NOOP(
"Gimbal Down");
489 static constexpr const char *_buttonActionGimbalUp = QT_TR_NOOP(
"Gimbal Up");
490 static constexpr const char *_buttonActionGimbalLeft = QT_TR_NOOP(
"Gimbal Left");
491 static constexpr const char *_buttonActionGimbalRight = QT_TR_NOOP(
"Gimbal Right");
492 static constexpr const char *_buttonActionGimbalCenter = QT_TR_NOOP(
"Gimbal Center");
493 static constexpr const char *_buttonActionGimbalYawLock = QT_TR_NOOP(
"Gimbal Yaw Lock");
494 static constexpr const char *_buttonActionGimbalYawFollow = QT_TR_NOOP(
"Gimbal Yaw Follow");
495 static constexpr const char *_buttonActionEmergencyStop = QT_TR_NOOP(
"Emergency Stop");
496 static constexpr const char *_buttonActionGripperGrab = QT_TR_NOOP(
"Gripper Grab");
497 static constexpr const char *_buttonActionGripperRelease = QT_TR_NOOP(
"Gripper Release");
498 static constexpr const char *_buttonActionGripperHold = QT_TR_NOOP(
"Gripper Hold");
499 static constexpr const char *_buttonActionLandingGearDeploy= QT_TR_NOOP(
"Landing gear deploy");
500 static constexpr const char *_buttonActionLandingGearRetract= QT_TR_NOOP(
"Landing gear retract");
501 static constexpr const char *_buttonActionMotorInterlockEnable= QT_TR_NOOP(
"Motor Interlock enable");
502 static constexpr const char *_buttonActionMotorInterlockDisable= QT_TR_NOOP(
"Motor Interlock disable");
Q_DECLARE_LOGGING_CATEGORY(AndroidSerialLog)
virtual void setPlayerIndex(int index)
virtual bool hasAccelerometer() const
void setLinkedGroupId(const QString &groupId)
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)
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 setVirtualTouchpad(int touchpad, int finger, bool down, float x, float y, float pressure)
virtual QVariantMap getTouchpadFinger(int touchpad, int finger) const
virtual bool requiresCalibration() const
QString linkedGroupId() const
HOTAS/Multi-device linking (devices with same groupId act as single joystick)
virtual bool hasAxis(int axis) const
virtual int ballCount() const
virtual void rumble(quint16 lowFreq, quint16 highFreq, quint32 durationMs)
QString disabledActionName() const
virtual bool addMapping(const QString &mapping)
void batteryStateChanged()
virtual QString deviceType() const
virtual bool isVirtual() const
virtual int touchpadCount() const
virtual bool hasMonoLED() const
RemoteControlCalibrationController::StickFunction mapAxisFunctionToRCCStickFunction(AxisFunction_t axisFunction) const
virtual bool isGamepad() const
HatDirection
Standard gamepad hat/D-pad directions.
virtual void rumbleTriggers(quint16 left, quint16 right, quint32 durationMs)
const QmlObjectListModel * assignableActions() const
virtual QString axisLabel(int axis) const
virtual QString gamepadType() const
void setLinkedGroupRole(const QString &role)
void setFlightMode(const QString &flightMode)
virtual QVariantMap getButtonBinding(int button) const
virtual float accelerometerDataRate() const
virtual QVariantMap getAxisInitialState(int axis) const
void motorInterlock(bool enable)
QString name READ name CONSTANT(JoystickSettings *settings READ settings CONSTANT) 1(int axisCount READ axisCount CONSTANT) 1(int buttonCount READ buttonCount CONSTANT) 1(bool requiresCalibration READ requiresCalibration CONSTANT) 1(bool hasRumble READ hasRumble CONSTANT) 1(bool hasRumbleTriggers READ hasRumbleTriggers CONSTANT) 1(bool hasLED READ hasLED CONSTANT) 1(QString guid READ guid CONSTANT) 1(quint16 vendorId READ vendorId CONSTANT) 1(quint16 productId READ productId CONSTANT) 1(QString serial READ serial CONSTANT) 1(QString deviceType READ deviceType CONSTANT) 1(int playerIndex READ playerIndex WRITE setPlayerIndex NOTIFY playerIndexChanged) 1(int batteryPercent READ batteryPercent NOTIFY batteryStateChanged) 1(QString powerState READ powerState NOTIFY batteryStateChanged) 1(bool isGamepad READ isGamepad CONSTANT) 1(QString gamepadType READ gamepadType CONSTANT) 1(QString path READ path CONSTANT) 1(bool isVirtual READ isVirtual CONSTANT) 1(quint16 firmwareVersion READ firmwareVersion CONSTANT) 1(QString connectionType READ connectionType CONSTANT) 1(int ballCount READ ballCount CONSTANT) 1(const QmlObjectListModel *assignableActions READ assignableActions NOTIFY assignableActionsChanged) 1(QString disabledActionName READ disabledActionName CONSTANT) 1(QStringList assignableActionTitles READ assignableActionTitles NOTIFY assignableActionsChanged) 1(QStringList buttonActions READ buttonActions NOTIFY buttonActionsChanged) 1(QString buttonActionNone READ buttonActionNone CONSTANT) 1(QString linkedGroupId READ linkedGroupId WRITE setLinkedGroupId NOTIFY linkedGroupChanged) 1(QString linkedGroupRole READ linkedGroupRole WRITE setLinkedGroupRole NOTIFY linkedGroupChanged) Joystick(const QString &name
virtual QString getMapping() const
static QString axisFunctionToString(AxisFunction_t function)
void setFunctionForChannel(RemoteControlCalibrationController::StickFunction stickFunction, int channel)
void axisValues(float roll, float pitch, float yaw, float throttle)
virtual void hapticRumbleStop()
virtual QString buttonLabel(int button) const
virtual bool hasPlayerLED() const
void buttonActionsChanged()
virtual QVariantMap getBall(int ball) const
@ ButtonEventDownTransition
@ ButtonEventUpTransition
void assignableActionsChanged()
virtual QVector3D accelerometerData() const
static constexpr int AxisMin
virtual int touchpadFingerCount(int touchpad) const
virtual bool hasButton(int button) const
void unknownAction(const QString &action)
void playerIndexChanged()
virtual quint16 vendorId() const
QString name READ name int int int hatCount
virtual float gyroscopeDataRate() const
virtual QVector3D gyroscopeData() 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 int playerIndex() const
QString getButtonAction(int button) const
virtual bool hasGyroscope() const
virtual bool sendEffect(const QByteArray &data)
virtual QString serial() const
void connectionStateChanged(const QString &newState)
virtual QString realGamepadType() const
void stepZoom(int direction)
virtual QVariantMap getAxisBinding(int axis) const
QStringList buttonActions() const
AxisFunction_t mapRCCStickFunctionToAxisFunction(RemoteControlCalibrationController::StickFunction stickFunction) const
void startConfiguration()
Tells the joystick that the configuration UI is being displayed so it can do any special processing r...
virtual QString connectionType() const
QString name READ name int axisCount
virtual quint16 productId() const
Joystick::AxisCalibration_t getAxisCalibration(int axis) const
virtual bool hasRumble() const
void setAxisCalibration(int axis, const AxisCalibration_t &calibration)
void gripperAction(QGCMAVLink::GripperActions gripperAction)
QString name READ name int int buttonCount
QString buttonActionNone() const
void startContinuousZoom(int direction)
JoystickSettings * settings()
virtual QString getMappingForGUID(const QString &guid) const
virtual QString buttonLabelForType(int button) const
void stopContinuousZoom()
virtual bool setMapping(const QString &mapping)
virtual void setLED(quint8 red, quint8 green, quint8 blue)
GamepadAxis
Standard gamepad axis indices.
bool getButtonRepeat(int button)
virtual bool setGyroscopeEnabled(bool enabled)
virtual bool hasLED() const
virtual bool hapticRumblePlay(float strength, quint32 durationMs)
static constexpr int AxisMax
void setButtonAction(int button, const QString &action)
QString name READ name int int int QObject * parent
void stepCamera(int direction)
void accelerometerDataUpdated(const QVector3D &data)
void setVtolInFwdFlight(bool set)
virtual bool setVirtualButton(int button, bool down)
virtual int hapticEffectsCount() const
void stepStream(int direction)
virtual QString connectionState() const
void landingGearRetract()
virtual bool setAccelerometerEnabled(bool enabled)
GamepadButton
Standard gamepad button indices.
virtual QString path() const
virtual bool hapticRumbleSupported() const
void gimbalPitchStart(int direction)
virtual bool hasHaptic() const
virtual bool setVirtualBall(int ball, int dx, int dy)
virtual bool hapticRumbleInit()
QStringList assignableActionTitles() const
void gyroscopeDataUpdated(const QVector3D &data)
virtual QString guid() const
void linkedGroupChanged()
void rawChannelValuesChanged(QVector< int > channelValues)
Signalled during PollingForConfiguration.
QString linkedGroupRole() const
void gimbalYawStart(int direction)
void setButtonRepeat(int button, bool repeat)
virtual QString powerState() const
virtual bool setVirtualAxis(int axis, int value)
virtual bool sendVirtualSensorData(int sensorType, float x, float y, float z)
virtual bool hasRGBLED() const
virtual bool setVirtualHat(int hat, quint8 value)