diff --git a/src/Joystick/Joystick.cc b/src/Joystick/Joystick.cc index 27cc1336ed8b9d6fd5d7797ab6c9110e8c578f80..4bf624587df7034f5a271b1ec37f37e0bebc14da 100644 --- a/src/Joystick/Joystick.cc +++ b/src/Joystick/Joystick.cc @@ -108,40 +108,7 @@ Joystick::Joystick(const QString& name, int axisCount, int buttonCount, int hatC _rgButtonValues[i] = BUTTON_UP; _buttonActionArray.append(nullptr); } - //-- Available Actions - _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionNone)); - _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionArm)); - _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionDisarm)); - _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionToggleArm)); - if (_activeVehicle) { - QStringList list = _activeVehicle->flightModes(); - foreach(auto mode, list) { - _assignableButtonActions.append(new AssignableButtonAction(this, mode)); - } - } - _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionVTOLFixedWing)); - _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionVTOLMultiRotor)); - _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionContinuousZoomIn, true)); - _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionContinuousZoomOut, true)); - _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionStepZoomIn, true)); - _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionStepZoomOut, true)); - _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionNextStream)); - _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionPreviousStream)); - _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionNextCamera)); - _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionPreviousCamera)); - _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionTriggerCamera)); - _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionStartVideoRecord)); - _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionStopVideoRecord)); - _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionToggleVideoRecord)); - _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionGimbalDown, true)); - _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionGimbalUp, true)); - _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionGimbalLeft, true)); - _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionGimbalRight, true)); - _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionGimbalCenter)); - for(int i = 0; i < _assignableButtonActions.count(); i++) { - AssignableButtonAction* p = qobject_cast(_assignableButtonActions[i]); - _availableActionTitles << p->action(); - } + _buildActionList(_multiVehicleManager->activeVehicle()); _updateTXModeSettingsKey(_multiVehicleManager->activeVehicle()); _loadSettings(); connect(_multiVehicleManager, &MultiVehicleManager::activeVehicleChanged, this, &Joystick::_activeVehicleChanged); @@ -155,7 +122,7 @@ Joystick::~Joystick() delete[] _rgAxisValues; delete[] _rgCalibration; delete[] _rgButtonValues; - _assignableButtonActions.deleteListAndContents(); + _assignableButtonActions.clearAndDeleteContents(); for (int button = 0; button < _totalButtonCount; button++) { if(_buttonActionArray[button]) { _buttonActionArray[button]->deleteLater(); @@ -690,6 +657,8 @@ void Joystick::startPolling(Vehicle* vehicle) } // Update qml in case of joystick transition emit calibratedChanged(_calibrated); + // Build action list + _buildActionList(vehicle); // Only connect the new vehicle if it wants joystick data if (vehicle->joystickEnabled()) { _pollingStartedForCalibration = false; @@ -1066,3 +1035,44 @@ int Joystick::_findAssignableButtonAction(const QString& action) return -1; } +void Joystick::_buildActionList(Vehicle* activeVehicle) +{ + if(_assignableButtonActions.count()) + _assignableButtonActions.clearAndDeleteContents(); + _availableActionTitles.clear(); + //-- Available Actions + _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionNone)); + _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionArm)); + _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionDisarm)); + _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionToggleArm)); + if (activeVehicle) { + QStringList list = activeVehicle->flightModes(); + foreach(auto mode, list) { + _assignableButtonActions.append(new AssignableButtonAction(this, mode)); + } + } + _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionVTOLFixedWing)); + _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionVTOLMultiRotor)); + _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionContinuousZoomIn, true)); + _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionContinuousZoomOut, true)); + _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionStepZoomIn, true)); + _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionStepZoomOut, true)); + _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionNextStream)); + _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionPreviousStream)); + _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionNextCamera)); + _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionPreviousCamera)); + _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionTriggerCamera)); + _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionStartVideoRecord)); + _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionStopVideoRecord)); + _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionToggleVideoRecord)); + _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionGimbalDown, true)); + _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionGimbalUp, true)); + _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionGimbalLeft, true)); + _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionGimbalRight, true)); + _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionGimbalCenter)); + for(int i = 0; i < _assignableButtonActions.count(); i++) { + AssignableButtonAction* p = qobject_cast(_assignableButtonActions[i]); + _availableActionTitles << p->action(); + } + emit assignableActionsChanged(); +} diff --git a/src/Joystick/Joystick.h b/src/Joystick/Joystick.h index 17a5d95603cd5c2ab22bf745345cae6870c1118e..52baa95befe027f9b415bfd891c824d3b532f403 100644 --- a/src/Joystick/Joystick.h +++ b/src/Joystick/Joystick.h @@ -93,8 +93,8 @@ public: Q_PROPERTY(QStringList buttonActions READ buttonActions NOTIFY buttonActionsChanged) //-- Actions that can be assigned to buttons - Q_PROPERTY(QmlObjectListModel* assignableActions READ assignableActions CONSTANT) - Q_PROPERTY(QStringList assignableActionTitles READ assignableActionTitles CONSTANT) + Q_PROPERTY(QmlObjectListModel* assignableActions READ assignableActions NOTIFY assignableActionsChanged) + Q_PROPERTY(QStringList assignableActionTitles READ assignableActionTitles NOTIFY assignableActionsChanged) Q_PROPERTY(QString disabledActionName READ disabledActionName CONSTANT) Q_PROPERTY(bool gimbalEnabled READ gimbalEnabled WRITE setGimbalEnabled NOTIFY gimbalEnabledChanged) @@ -180,6 +180,7 @@ signals: void rawButtonPressedChanged (int index, int pressed); void calibratedChanged (bool calibrated); void buttonActionsChanged (); + void assignableActionsChanged (); void throttleModeChanged (int mode); void negativeThrustChanged (bool allowNegative); void exponentialChanged (float exponential); @@ -230,6 +231,7 @@ protected: bool _validButton (int button); void _handleAxis (); void _handleButtons (); + void _buildActionList (Vehicle* activeVehicle); void _pitchStep (int direction); void _yawStep (int direction);