Browse Source

Continue WIP

QGC4.4
Gus Grubba 6 years ago
parent
commit
17370aa4ae
  1. 219
      src/Joystick/Joystick.cc
  2. 168
      src/Joystick/Joystick.h
  3. 42
      src/VehicleSetup/JoystickConfigButtons.qml

219
src/Joystick/Joystick.cc

@ -41,13 +41,16 @@ const char* Joystick::_vtolTXModeSettingsKey = "TXMode_VTOL";
const char* Joystick::_submarineTXModeSettingsKey = "TXMode_Submarine"; const char* Joystick::_submarineTXModeSettingsKey = "TXMode_Submarine";
const char* Joystick::_gimbalSettingsKey = "GimbalEnabled"; const char* Joystick::_gimbalSettingsKey = "GimbalEnabled";
const char* Joystick::_buttonActionNone = QT_TR_NOOP("No Action");
const char* Joystick::_buttonActionArm = QT_TR_NOOP("Arm"); const char* Joystick::_buttonActionArm = QT_TR_NOOP("Arm");
const char* Joystick::_buttonActionDisarm = QT_TR_NOOP("Disarm"); const char* Joystick::_buttonActionDisarm = QT_TR_NOOP("Disarm");
const char* Joystick::_buttonActionToggleArm = QT_TR_NOOP("Toggle Arm"); const char* Joystick::_buttonActionToggleArm = QT_TR_NOOP("Toggle Arm");
const char* Joystick::_buttonActionVTOLFixedWing = QT_TR_NOOP("VTOL: Fixed Wing"); const char* Joystick::_buttonActionVTOLFixedWing = QT_TR_NOOP("VTOL: Fixed Wing");
const char* Joystick::_buttonActionVTOLMultiRotor = QT_TR_NOOP("VTOL: Multi-Rotor"); const char* Joystick::_buttonActionVTOLMultiRotor = QT_TR_NOOP("VTOL: Multi-Rotor");
const char* Joystick::_buttonActionZoomIn = QT_TR_NOOP("Zoom In"); const char* Joystick::_buttonActionContinuousZoomIn = QT_TR_NOOP("Continuous Zoom In");
const char* Joystick::_buttonActionZoomOut = QT_TR_NOOP("Zoom Out"); const char* Joystick::_buttonActionContinuousZoomOut = QT_TR_NOOP("Continuous Zoom Out");
const char* Joystick::_buttonActionStepZoomIn = QT_TR_NOOP("Step Zoom In");
const char* Joystick::_buttonActionStepZoomOut = QT_TR_NOOP("Step Zoom Out");
const char* Joystick::_buttonActionNextStream = QT_TR_NOOP("Next Video Stream"); const char* Joystick::_buttonActionNextStream = QT_TR_NOOP("Next Video Stream");
const char* Joystick::_buttonActionPreviousStream = QT_TR_NOOP("Previous Video Stream"); const char* Joystick::_buttonActionPreviousStream = QT_TR_NOOP("Previous Video Stream");
const char* Joystick::_buttonActionNextCamera = QT_TR_NOOP("Next Camera"); const char* Joystick::_buttonActionNextCamera = QT_TR_NOOP("Next Camera");
@ -73,7 +76,13 @@ const char* Joystick::_rgFunctionSettingsKey[Joystick::maxFunction] = {
int Joystick::_transmitterMode = 2; int Joystick::_transmitterMode = 2;
ButtonAction::ButtonAction(QObject* parent, QString action_, bool canRepeat_) AssignedButtonAction::AssignedButtonAction(QObject* parent, const QString name)
: QObject(parent)
, action(name)
{
}
AssignableButtonAction::AssignableButtonAction(QObject* parent, QString action_, bool canRepeat_)
: QObject(parent) : QObject(parent)
, _action(action_) , _action(action_)
, _repeat(canRepeat_) , _repeat(canRepeat_)
@ -97,11 +106,45 @@ Joystick::Joystick(const QString& name, int axisCount, int buttonCount, int hatC
} }
for (int i = 0; i < _totalButtonCount; i++) { for (int i = 0; i < _totalButtonCount; i++) {
_rgButtonValues[i] = BUTTON_UP; _rgButtonValues[i] = BUTTON_UP;
_buttonActionArray << nullptr; _buttonActionArray.append(nullptr);
} }
_updateTXModeSettingsKey(_multiVehicleManager->activeVehicle()); _updateTXModeSettingsKey(_multiVehicleManager->activeVehicle());
_loadSettings(); _loadSettings();
connect(_multiVehicleManager, &MultiVehicleManager::activeVehicleChanged, this, &Joystick::_activeVehicleChanged); connect(_multiVehicleManager, &MultiVehicleManager::activeVehicleChanged, this, &Joystick::_activeVehicleChanged);
//-- 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<AssignableButtonAction*>(_assignableButtonActions[i]);
_availableActionTitles << p->action();
}
} }
Joystick::~Joystick() Joystick::~Joystick()
@ -112,6 +155,7 @@ Joystick::~Joystick()
delete[] _rgAxisValues; delete[] _rgAxisValues;
delete[] _rgCalibration; delete[] _rgCalibration;
delete[] _rgButtonValues; delete[] _rgButtonValues;
_assignableButtonActions.deleteListAndContents();
for (int button = 0; button < _totalButtonCount; button++) { for (int button = 0; button < _totalButtonCount; button++) {
if(_buttonActionArray[button]) { if(_buttonActionArray[button]) {
_buttonActionArray[button]->deleteLater(); _buttonActionArray[button]->deleteLater();
@ -261,14 +305,14 @@ void Joystick::_loadSettings()
for (int button = 0; button < _totalButtonCount; button++) { for (int button = 0; button < _totalButtonCount; button++) {
QString a = settings.value(QString(_buttonActionNameKey).arg(button), QString()).toString(); QString a = settings.value(QString(_buttonActionNameKey).arg(button), QString()).toString();
if(!a.isEmpty()) { if(!a.isEmpty() && _findAssignableButtonAction(a) >= 0 && a != _buttonActionNone) {
if(_buttonActionArray[button]) { if(_buttonActionArray[button]) {
_buttonActionArray[button]->deleteLater(); _buttonActionArray[button]->deleteLater();
} }
AssignedButtonAction* ap = new AssignedButtonAction(); AssignedButtonAction* ap = new AssignedButtonAction(this, a);
ap->action = a;
ap->repeat = settings.value(QString(_buttonActionRepeatKey).arg(button), false).toBool(); ap->repeat = settings.value(QString(_buttonActionRepeatKey).arg(button), false).toBool();
ap->frequency = settings.value(QString(_buttonActionFrequencyKey).arg(button), 1).toInt(); ap->frequency = settings.value(QString(_buttonActionFrequencyKey).arg(button), 1).toInt();
if(ap->frequency > 25.0f) ap->frequency = 25.0f;
_buttonActionArray[button] = ap; _buttonActionArray[button] = ap;
qCDebug(JoystickLog) << "_loadSettings button:action" << button << _buttonActionArray[button]->action << _buttonActionArray[button]->repeat << _buttonActionArray[button]->frequency; qCDebug(JoystickLog) << "_loadSettings button:action" << button << _buttonActionArray[button]->action << _buttonActionArray[button]->repeat << _buttonActionArray[button]->frequency;
} }
@ -280,10 +324,24 @@ void Joystick::_loadSettings()
} }
} }
void Joystick::_saveSettings() void Joystick::_saveButtonSettings()
{ {
QSettings settings; QSettings settings;
settings.beginGroup(_settingsGroup);
settings.beginGroup(_name);
for (int button = 0; button < _totalButtonCount; button++) {
if(_buttonActionArray[button]) {
settings.setValue(QString(_buttonActionNameKey).arg(button), _buttonActionArray[button]->action);
settings.setValue(QString(_buttonActionRepeatKey).arg(button), _buttonActionArray[button]->repeat);
settings.setValue(QString(_buttonActionFrequencyKey).arg(button), _buttonActionArray[button]->frequency);
qCDebug(JoystickLog) << "_saveButtonSettings button:action" << button << _buttonActionArray[button]->action << _buttonActionArray[button]->repeat << _buttonActionArray[button]->frequency;
}
}
}
void Joystick::_saveSettings()
{
QSettings settings;
settings.beginGroup(_settingsGroup); settings.beginGroup(_settingsGroup);
// Transmitter mode is static // Transmitter mode is static
@ -292,7 +350,6 @@ void Joystick::_saveSettings()
settings.setValue(_txModeSettingsKey, _transmitterMode); settings.setValue(_txModeSettingsKey, _transmitterMode);
settings.beginGroup(_name); settings.beginGroup(_name);
settings.setValue(_calibratedSettingsKey, _calibrated); settings.setValue(_calibratedSettingsKey, _calibrated);
settings.setValue(_exponentialSettingsKey, _exponential); settings.setValue(_exponentialSettingsKey, _exponential);
settings.setValue(_accumulatorSettingsKey, _accumulator); settings.setValue(_accumulatorSettingsKey, _accumulator);
@ -331,20 +388,11 @@ void Joystick::_saveSettings()
// Write mode 2 mappings without changing mapping currently in use // Write mode 2 mappings without changing mapping currently in use
int temp[maxFunction]; int temp[maxFunction];
_remapAxes(_transmitterMode, 2, temp); _remapAxes(_transmitterMode, 2, temp);
for (int function = 0; function < maxFunction; function++) { for (int function = 0; function < maxFunction; function++) {
settings.setValue(_rgFunctionSettingsKey[function], temp[function]); settings.setValue(_rgFunctionSettingsKey[function], temp[function]);
qCDebug(JoystickLog) << "_saveSettings name:function:axis" << _name << function << _rgFunctionSettingsKey[function]; qCDebug(JoystickLog) << "_saveSettings name:function:axis" << _name << function << _rgFunctionSettingsKey[function];
} }
_saveButtonSettings();
for (int button = 0; button < _totalButtonCount; button++) {
if(_buttonActionArray[button]) {
settings.setValue(QString(_buttonActionNameKey).arg(button), _buttonActionArray[button]->action);
settings.setValue(QString(_buttonActionRepeatKey).arg(button), _buttonActionArray[button]->repeat);
settings.setValue(QString(_buttonActionFrequencyKey).arg(button), _buttonActionArray[button]->frequency);
qCDebug(JoystickLog) << "_saveSettings button:action" << button << _buttonActionArray[button]->action << _buttonActionArray[button]->repeat << _buttonActionArray[button]->frequency;
}
}
} }
// Relative mappings of axis functions between different TX modes // Relative mappings of axis functions between different TX modes
@ -496,7 +544,7 @@ void Joystick::_handleButtons()
QString buttonAction = _buttonActionArray[buttonIndex]->action; QString buttonAction = _buttonActionArray[buttonIndex]->action;
if (!buttonAction.isEmpty()) { if (!buttonAction.isEmpty()) {
qCDebug(JoystickLog) << "Single button triggered" << buttonIndex << buttonAction; qCDebug(JoystickLog) << "Single button triggered" << buttonIndex << buttonAction;
_buttonAction(buttonAction); _executeButtonAction(buttonAction);
} }
} else { } else {
//-- Process repeat buttons //-- Process repeat buttons
@ -506,7 +554,7 @@ void Joystick::_handleButtons()
QString buttonAction = _buttonActionArray[buttonIndex]->action; QString buttonAction = _buttonActionArray[buttonIndex]->action;
if (!buttonAction.isEmpty()) { if (!buttonAction.isEmpty()) {
qCDebug(JoystickLog) << "Repeat button triggered" << buttonIndex << buttonAction; qCDebug(JoystickLog) << "Repeat button triggered" << buttonIndex << buttonAction;
_buttonAction(buttonAction); _executeButtonAction(buttonAction);
} }
} }
} }
@ -719,73 +767,65 @@ int Joystick::getFunctionAxis(AxisFunction_t function)
return _rgFunctionAxis[function]; return _rgFunctionAxis[function];
} }
QList<ButtonAction*> Joystick::actions() void Joystick::setButtonRepeat(int button, bool repeat)
{ {
if(_actions.isEmpty()) { if (!_validButton(button) || !_buttonActionArray[button]) {
_actions << new ButtonAction(this, _buttonActionArm); return;
_actions << new ButtonAction(this, _buttonActionDisarm); }
_actions << new ButtonAction(this, _buttonActionToggleArm); _buttonActionArray[button]->repeat = repeat;
if (_activeVehicle) { _saveButtonSettings();
QStringList list = _activeVehicle->flightModes(); }
foreach(auto mode, list) {
_actions << new ButtonAction(this, mode); void Joystick::setButtonFrequency(int button, int freq)
} {
} if (!_validButton(button) || !_buttonActionArray[button]) {
_actions << new ButtonAction(this, _buttonActionVTOLFixedWing); return;
_actions << new ButtonAction(this, _buttonActionVTOLMultiRotor); }
_actions << new ButtonAction(this, _buttonActionZoomIn, true); _buttonActionArray[button]->frequency = freq;
_actions << new ButtonAction(this, _buttonActionZoomOut, true); _saveButtonSettings();
_actions << new ButtonAction(this, _buttonActionNextStream);
_actions << new ButtonAction(this, _buttonActionPreviousStream);
_actions << new ButtonAction(this, _buttonActionNextCamera);
_actions << new ButtonAction(this, _buttonActionPreviousCamera);
_actions << new ButtonAction(this, _buttonActionTriggerCamera);
_actions << new ButtonAction(this, _buttonActionStartVideoRecord);
_actions << new ButtonAction(this, _buttonActionStopVideoRecord);
_actions << new ButtonAction(this, _buttonActionToggleVideoRecord);
_actions << new ButtonAction(this, _buttonActionGimbalDown, true);
_actions << new ButtonAction(this, _buttonActionGimbalUp, true);
_actions << new ButtonAction(this, _buttonActionGimbalLeft, true);
_actions << new ButtonAction(this, _buttonActionGimbalRight, true);
_actions << new ButtonAction(this, _buttonActionGimbalCenter);
}
return _actions;
} }
void Joystick::setButtonAction(int button, const QString& action) void Joystick::setButtonAction(int button, const QString& action)
{ {
if (!_validButton(button)) { if (!_validButton(button)) {
qCWarning(JoystickLog) << "Invalid button index" << button;
return; return;
} }
if(action.isEmpty()) { qCWarning(JoystickLog) << "setButtonAction:" << button << action;
qDebug() << "setButtonAction:" << "None"; if(action.isEmpty() || action == _buttonActionNone) {
_buttonActionArray[button]->deleteLater(); if(_buttonActionArray[button]) {
_buttonActionArray[button] = nullptr; _buttonActionArray[button]->deleteLater();
_buttonActionArray[button] = nullptr;
}
} else { } else {
qDebug() << "setButtonAction:" << action;
if(!_buttonActionArray[button]) { if(!_buttonActionArray[button]) {
_buttonActionArray[button] = new AssignedButtonAction(); _buttonActionArray[button] = new AssignedButtonAction(this, action);
} else {
_buttonActionArray[button]->action = action;
//-- Make sure repeat is off if this action doesn't support repeats
int idx = _findAssignableButtonAction(action);
if(idx >= 0) {
AssignableButtonAction* p = qobject_cast<AssignableButtonAction*>(_assignableButtonActions[idx]);
if(!p->canRepeat()) {
_buttonActionArray[button]->repeat = false;
}
}
} }
_buttonActionArray[button]->action = action;
qCDebug(JoystickLog) << "_loadSettings button:action" << button << _buttonActionArray[button]->action << _buttonActionArray[button]->repeat << _buttonActionArray[button]->frequency;
} }
_saveSettings(); _saveButtonSettings();
emit actionTitlesChanged(actionTitles()); emit buttonActionsChanged();
} }
QString Joystick::getButtonAction(int button) QString Joystick::getButtonAction(int button)
{ {
if (!_validButton(button)) { if (_validButton(button)) {
qCWarning(JoystickLog) << "Invalid button index" << button; if(_buttonActionArray[button]) {
} return _buttonActionArray[button]->action;
if(_buttonActionArray[button]) { }
return _buttonActionArray[button]->action;
} }
return QString(); return QString(_buttonActionNone);
} }
QStringList Joystick::actionTitles() QStringList Joystick::buttonActions()
{ {
QStringList list; QStringList list;
for (int button = 0; button < _totalButtonCount; button++) { for (int button = 0; button < _totalButtonCount; button++) {
@ -794,7 +834,7 @@ QStringList Joystick::actionTitles()
return list; return list;
} }
int Joystick::throttleMode(void) int Joystick::throttleMode()
{ {
return _throttleMode; return _throttleMode;
} }
@ -813,7 +853,7 @@ void Joystick::setThrottleMode(int mode)
emit throttleModeChanged(_throttleMode); emit throttleModeChanged(_throttleMode);
} }
bool Joystick::negativeThrust(void) bool Joystick::negativeThrust()
{ {
return _negativeThrust; return _negativeThrust;
} }
@ -828,7 +868,7 @@ void Joystick::setNegativeThrust(bool allowNegative)
emit negativeThrustChanged(_negativeThrust); emit negativeThrustChanged(_negativeThrust);
} }
float Joystick::exponential(void) float Joystick::exponential()
{ {
return _exponential; return _exponential;
} }
@ -840,7 +880,7 @@ void Joystick::setExponential(float expo)
emit exponentialChanged(_exponential); emit exponentialChanged(_exponential);
} }
bool Joystick::accumulator(void) bool Joystick::accumulator()
{ {
return _accumulator; return _accumulator;
} }
@ -852,7 +892,7 @@ void Joystick::setAccumulator(bool accu)
emit accumulatorChanged(_accumulator); emit accumulatorChanged(_accumulator);
} }
bool Joystick::deadband(void) bool Joystick::deadband()
{ {
return _deadband; return _deadband;
} }
@ -863,7 +903,7 @@ void Joystick::setDeadband(bool deadband)
_saveSettings(); _saveSettings();
} }
bool Joystick::circleCorrection(void) bool Joystick::circleCorrection()
{ {
return _circleCorrection; return _circleCorrection;
} }
@ -890,8 +930,8 @@ void Joystick::setGimbalEnabled(bool set)
void Joystick::setFrequency(float val) void Joystick::setFrequency(float val)
{ {
//-- Arbitrary limits //-- Arbitrary limits
if(val < 0.25f) val = 0.25f; if(val < 0.25f) val = 0.25f;
if(val > 100.0f) val = 100.0f; if(val > 50.0f) val = 50.0f;
_frequency = val; _frequency = val;
_saveSettings(); _saveSettings();
emit frequencyChanged(); emit frequencyChanged();
@ -910,9 +950,9 @@ void Joystick::setCalibrationMode(bool calibrating)
} }
void Joystick::_buttonAction(const QString& action) void Joystick::_executeButtonAction(const QString& action)
{ {
if (!_activeVehicle || !_activeVehicle->joystickEnabled()) { if (!_activeVehicle || !_activeVehicle->joystickEnabled() || action == _buttonActionNone) {
return; return;
} }
if (action == _buttonActionArm) { if (action == _buttonActionArm) {
@ -927,8 +967,10 @@ void Joystick::_buttonAction(const QString& action)
emit setVtolInFwdFlight(false); emit setVtolInFwdFlight(false);
} else if (_activeVehicle->flightModes().contains(action)) { } else if (_activeVehicle->flightModes().contains(action)) {
emit setFlightMode(action); emit setFlightMode(action);
} else if(action == _buttonActionZoomIn || action == _buttonActionZoomOut) { } else if(action == _buttonActionContinuousZoomIn || action == _buttonActionContinuousZoomOut) {
emit stepZoom(action == _buttonActionZoomIn ? 1 : -1); emit startContinuousZoom(action == _buttonActionStepZoomIn ? 1 : -1);
} else if(action == _buttonActionStepZoomIn || action == _buttonActionStepZoomOut) {
emit stepZoom(action == _buttonActionStepZoomIn ? 1 : -1);
} else if(action == _buttonActionNextStream || action == _buttonActionPreviousStream) { } else if(action == _buttonActionNextStream || action == _buttonActionPreviousStream) {
emit stepStream(action == _buttonActionNextStream ? 1 : -1); emit stepStream(action == _buttonActionNextStream ? 1 : -1);
} else if(action == _buttonActionNextCamera || action == _buttonActionPreviousCamera) { } else if(action == _buttonActionNextCamera || action == _buttonActionPreviousCamera) {
@ -963,6 +1005,19 @@ bool Joystick::_validAxis(int axis)
bool Joystick::_validButton(int button) bool Joystick::_validButton(int button)
{ {
return button >= 0 && button < _totalButtonCount; if(button >= 0 && button < _totalButtonCount)
return true;
qCWarning(JoystickLog) << "Invalid button index" << button;
return false;
}
int Joystick::_findAssignableButtonAction(const QString& action)
{
for(int i = 0; i < _assignableButtonActions.count(); i++) {
AssignableButtonAction* p = qobject_cast<AssignableButtonAction*>(_assignableButtonActions[i]);
if(p->action() == action)
return i;
}
return -1;
} }

168
src/Joystick/Joystick.h

@ -22,9 +22,10 @@ Q_DECLARE_LOGGING_CATEGORY(JoystickLog)
Q_DECLARE_LOGGING_CATEGORY(JoystickValuesLog) Q_DECLARE_LOGGING_CATEGORY(JoystickValuesLog)
//-- Action assigned to button //-- Action assigned to button
class AssignedButtonAction : public QObject { class AssignedButtonAction : public QObject {
Q_OBJECT Q_OBJECT
public: public:
AssignedButtonAction(QObject* parent, const QString name);
QString action; QString action;
QTime buttonTime; QTime buttonTime;
bool repeat = false; bool repeat = false;
@ -32,14 +33,14 @@ public:
}; };
//-- Assignable Button Action //-- Assignable Button Action
class ButtonAction : public QObject { class AssignableButtonAction : public QObject {
Q_OBJECT Q_OBJECT
public: public:
ButtonAction(QObject* parent, QString action_, bool canRepeat_ = false); AssignableButtonAction(QObject* parent, QString action_, bool canRepeat_ = false);
Q_PROPERTY(QString action READ action CONSTANT) Q_PROPERTY(QString action READ action CONSTANT)
Q_PROPERTY(bool canRepeat READ canRepeat CONSTANT) Q_PROPERTY(bool canRepeat READ canRepeat CONSTANT)
QString action () { return _action; } QString action () { return _action; }
bool repeat () { return _repeat; } bool canRepeat () { return _repeat; }
private: private:
QString _action; QString _action;
bool _repeat = false; bool _repeat = false;
@ -88,19 +89,27 @@ public:
Q_PROPERTY(int totalButtonCount READ totalButtonCount CONSTANT) Q_PROPERTY(int totalButtonCount READ totalButtonCount CONSTANT)
Q_PROPERTY(int axisCount READ axisCount CONSTANT) Q_PROPERTY(int axisCount READ axisCount CONSTANT)
Q_PROPERTY(bool requiresCalibration READ requiresCalibration CONSTANT) Q_PROPERTY(bool requiresCalibration READ requiresCalibration CONSTANT)
Q_PROPERTY(QList<ButtonAction*> actions READ actions CONSTANT)
Q_PROPERTY(QStringList actionTitles READ actionTitles NOTIFY actionTitlesChanged)
Q_PROPERTY(bool gimbalEnabled READ gimbalEnabled WRITE setGimbalEnabled NOTIFY gimbalEnabledChanged) //-- Actions assigned to buttons
Q_PROPERTY(int throttleMode READ throttleMode WRITE setThrottleMode NOTIFY throttleModeChanged) Q_PROPERTY(QStringList buttonActions READ buttonActions NOTIFY buttonActionsChanged)
Q_PROPERTY(float frequency READ frequency WRITE setFrequency NOTIFY frequencyChanged)
Q_PROPERTY(bool negativeThrust READ negativeThrust WRITE setNegativeThrust NOTIFY negativeThrustChanged)
Q_PROPERTY(float exponential READ exponential WRITE setExponential NOTIFY exponentialChanged)
Q_PROPERTY(bool accumulator READ accumulator WRITE setAccumulator NOTIFY accumulatorChanged)
Q_PROPERTY(bool circleCorrection READ circleCorrection WRITE setCircleCorrection NOTIFY circleCorrectionChanged)
Q_INVOKABLE void setButtonAction (int button, const QString& action); //-- Actions that can be assigned to buttons
Q_INVOKABLE QString getButtonAction (int button); Q_PROPERTY(QmlObjectListModel* assignableActions READ assignableActions CONSTANT)
Q_PROPERTY(QStringList assignableActionTitles READ assignableActionTitles CONSTANT)
Q_PROPERTY(QString disabledActionName READ disabledActionName CONSTANT)
Q_PROPERTY(bool gimbalEnabled READ gimbalEnabled WRITE setGimbalEnabled NOTIFY gimbalEnabledChanged)
Q_PROPERTY(int throttleMode READ throttleMode WRITE setThrottleMode NOTIFY throttleModeChanged)
Q_PROPERTY(float frequency READ frequency WRITE setFrequency NOTIFY frequencyChanged)
Q_PROPERTY(bool negativeThrust READ negativeThrust WRITE setNegativeThrust NOTIFY negativeThrustChanged)
Q_PROPERTY(float exponential READ exponential WRITE setExponential NOTIFY exponentialChanged)
Q_PROPERTY(bool accumulator READ accumulator WRITE setAccumulator NOTIFY accumulatorChanged)
Q_PROPERTY(bool circleCorrection READ circleCorrection WRITE setCircleCorrection NOTIFY circleCorrectionChanged)
Q_INVOKABLE void setButtonRepeat (int button, bool repeat);
Q_INVOKABLE void setButtonFrequency (int button, int freq);
Q_INVOKABLE void setButtonAction (int button, const QString& action);
Q_INVOKABLE QString getButtonAction (int button);
// Property accessors // Property accessors
@ -108,8 +117,11 @@ public:
int totalButtonCount () { return _totalButtonCount; } int totalButtonCount () { return _totalButtonCount; }
int axisCount () { return _axisCount; } int axisCount () { return _axisCount; }
bool gimbalEnabled () { return _gimbalEnabled; } bool gimbalEnabled () { return _gimbalEnabled; }
QList<ButtonAction*> actions (); QStringList buttonActions ();
QStringList actionTitles ();
QmlObjectListModel* assignableActions () { return &_assignableButtonActions; }
QStringList assignableActionTitles () { return _availableActionTitles; }
QString disabledActionName () { return _buttonActionNone; }
void setGimbalEnabled (bool set); void setGimbalEnabled (bool set);
@ -132,53 +144,45 @@ public:
*/ */
virtual bool requiresCalibration(void) { return true; } virtual bool requiresCalibration(void) { return true; }
int throttleMode(void); int throttleMode ();
void setThrottleMode(int mode); void setThrottleMode (int mode);
bool negativeThrust(void); bool negativeThrust ();
void setNegativeThrust(bool allowNegative); void setNegativeThrust (bool allowNegative);
float exponential(void); float exponential ();
void setExponential(float expo); void setExponential (float expo);
bool accumulator(void); bool accumulator ();
void setAccumulator(bool accu); void setAccumulator (bool accu);
bool deadband(void); bool deadband ();
void setDeadband(bool accu); void setDeadband (bool accu);
bool circleCorrection(void); bool circleCorrection ();
void setCircleCorrection(bool circleCorrection); void setCircleCorrection(bool circleCorrection);
void setTXMode(int mode); void setTXMode (int mode);
int getTXMode(void) { return _transmitterMode; } int getTXMode () { return _transmitterMode; }
/// Set the current calibration mode /// Set the current calibration mode
void setCalibrationMode(bool calibrating); void setCalibrationMode (bool calibrating);
float frequency(); float frequency ();
void setFrequency(float val); void setFrequency (float val);
signals: signals:
void calibratedChanged(bool calibrated);
// The raw signals are only meant for use by calibration // The raw signals are only meant for use by calibration
void rawAxisValueChanged(int index, int value); void rawAxisValueChanged (int index, int value);
void rawButtonPressedChanged(int index, int pressed); void rawButtonPressedChanged (int index, int pressed);
void calibratedChanged (bool calibrated);
void actionTitlesChanged(QStringList actions); void buttonActionsChanged ();
void throttleModeChanged (int mode);
void throttleModeChanged(int mode); void negativeThrustChanged (bool allowNegative);
void exponentialChanged (float exponential);
void negativeThrustChanged(bool allowNegative); void accumulatorChanged (bool accumulator);
void enabledChanged (bool enabled);
void exponentialChanged(float exponential); void circleCorrectionChanged (bool circleCorrection);
void accumulatorChanged(bool accumulator);
void enabledChanged(bool enabled);
void circleCorrectionChanged(bool circleCorrection);
/// Signal containing new joystick information /// Signal containing new joystick information
/// @param roll Range is -1:1, negative meaning roll left, positive meaning roll right /// @param roll Range is -1:1, negative meaning roll left, positive meaning roll right
@ -186,33 +190,37 @@ signals:
/// @param yaw Range is -1:1, negative meaning yaw left, positive meaning yaw right /// @param yaw Range is -1:1, negative meaning yaw left, positive meaning yaw right
/// @param throttle Range is 0:1, 0 meaning no throttle, 1 meaning full throttle /// @param throttle Range is 0:1, 0 meaning no throttle, 1 meaning full throttle
/// @param mode See Vehicle::JoystickMode_t enum /// @param mode See Vehicle::JoystickMode_t enum
void manualControl (float roll, float pitch, float yaw, float throttle, quint16 buttons, int joystickMmode); void manualControl (float roll, float pitch, float yaw, float throttle, quint16 buttons, int joystickMmode);
void manualControlGimbal (float gimbalPitch, float gimbalYaw); void manualControlGimbal (float gimbalPitch, float gimbalYaw);
void buttonActionTriggered (int action); void buttonActionTriggered (int action);
void gimbalEnabledChanged (); void gimbalEnabledChanged ();
void frequencyChanged (); void frequencyChanged ();
void stepZoom (int direction); void startContinuousZoom (int direction);
void stepCamera (int direction); void stopContinuousZoom ();
void stepStream (int direction); void stepZoom (int direction);
void triggerCamera (); void stepCamera (int direction);
void startVideoRecord (); void stepStream (int direction);
void stopVideoRecord (); void triggerCamera ();
void toggleVideoRecord (); void startVideoRecord ();
void gimbalPitchStep (int direction); void stopVideoRecord ();
void gimbalYawStep (int direction); void toggleVideoRecord ();
void centerGimbal (); void gimbalPitchStep (int direction);
void setArmed (bool arm); void gimbalYawStep (int direction);
void setVtolInFwdFlight (bool set); void centerGimbal ();
void setFlightMode (const QString& flightMode); void setArmed (bool arm);
void setVtolInFwdFlight (bool set);
void setFlightMode (const QString& flightMode);
protected: protected:
void _setDefaultCalibration (); void _setDefaultCalibration ();
void _saveSettings (); void _saveSettings ();
void _saveButtonSettings ();
void _loadSettings (); void _loadSettings ();
float _adjustRange (int value, Calibration_t calibration, bool withDeadbands); float _adjustRange (int value, Calibration_t calibration, bool withDeadbands);
void _buttonAction (const QString& action); void _executeButtonAction (const QString& action);
int _findAssignableButtonAction(const QString& action);
bool _validAxis (int axis); bool _validAxis (int axis);
bool _validButton (int button); bool _validButton (int button);
void _handleAxis (); void _handleAxis ();
@ -272,9 +280,10 @@ protected:
int _rgFunctionAxis[maxFunction] = {}; int _rgFunctionAxis[maxFunction] = {};
QTime _axisTime; QTime _axisTime;
QList<ButtonAction*> _actions; QmlObjectListModel _assignableButtonActions;
QList<AssignedButtonAction*> _buttonActionArray; QList<AssignedButtonAction*> _buttonActionArray;
MultiVehicleManager* _multiVehicleManager = nullptr; QStringList _availableActionTitles;
MultiVehicleManager* _multiVehicleManager = nullptr;
private: private:
static const char* _rgFunctionSettingsKey[maxFunction]; static const char* _rgFunctionSettingsKey[maxFunction];
@ -298,13 +307,16 @@ private:
static const char* _submarineTXModeSettingsKey; static const char* _submarineTXModeSettingsKey;
static const char* _gimbalSettingsKey; static const char* _gimbalSettingsKey;
static const char* _buttonActionNone;
static const char* _buttonActionArm; static const char* _buttonActionArm;
static const char* _buttonActionDisarm; static const char* _buttonActionDisarm;
static const char* _buttonActionToggleArm; static const char* _buttonActionToggleArm;
static const char* _buttonActionVTOLFixedWing; static const char* _buttonActionVTOLFixedWing;
static const char* _buttonActionVTOLMultiRotor; static const char* _buttonActionVTOLMultiRotor;
static const char* _buttonActionZoomIn; static const char* _buttonActionStepZoomIn;
static const char* _buttonActionZoomOut; static const char* _buttonActionStepZoomOut;
static const char* _buttonActionContinuousZoomIn;
static const char* _buttonActionContinuousZoomOut;
static const char* _buttonActionNextStream; static const char* _buttonActionNextStream;
static const char* _buttonActionPreviousStream; static const char* _buttonActionPreviousStream;
static const char* _buttonActionNextCamera; static const char* _buttonActionNextCamera;

42
src/VehicleSetup/JoystickConfigButtons.qml

@ -46,11 +46,7 @@ Item {
Row { Row {
spacing: ScreenTools.defaultFontPixelWidth spacing: ScreenTools.defaultFontPixelWidth
property bool pressed property bool pressed
QGCCheckBox { property var currentAction: _activeJoystick ? _activeJoystick.assignableActions.get(buttonActionCombo.currentIndex) : null
anchors.verticalCenter: parent.verticalCenter
checked: _activeJoystick ? _activeJoystick.actionTitles[modelData] !== "" : false
onClicked: _activeJoystick.setButtonAction(modelData, checked ? buttonActionCombo.textAt(buttonActionCombo.currentIndex) : "")
}
Rectangle { Rectangle {
anchors.verticalCenter: parent.verticalCenter anchors.verticalCenter: parent.verticalCenter
width: ScreenTools.defaultFontPixelHeight * 1.5 width: ScreenTools.defaultFontPixelHeight * 1.5
@ -69,19 +65,47 @@ Item {
QGCComboBox { QGCComboBox {
id: buttonActionCombo id: buttonActionCombo
width: ScreenTools.defaultFontPixelWidth * 26 width: ScreenTools.defaultFontPixelWidth * 26
model: _activeJoystick ? _activeJoystick.actions : [] model: _activeJoystick ? _activeJoystick.assignableActionTitles : []
onActivated: _activeJoystick.setButtonAction(modelData, textAt(index)) onActivated: {
Component.onCompleted: currentIndex = find(_activeJoystick.actionTitles[modelData]) _activeJoystick.setButtonAction(modelData, textAt(index))
}
Component.onCompleted: {
if(_activeJoystick) {
var i = find(_activeJoystick.buttonActions[modelData])
if(i < 0) i = 0
currentIndex = 0
}
}
} }
QGCCheckBox { QGCCheckBox {
id: repeatCheck id: repeatCheck
text: qsTr("Repeat") text: qsTr("Repeat")
enabled: currentAction && _activeJoystick.calibrated && currentAction.canRepeat
onClicked: {
_activeJoystick.setButtonRepeat(modelData, checked)
}
anchors.verticalCenter: parent.verticalCenter anchors.verticalCenter: parent.verticalCenter
} }
QGCComboBox { QGCComboBox {
width: ScreenTools.defaultFontPixelWidth * 10 width: ScreenTools.defaultFontPixelWidth * 10
model: ["1Hz","2Hz","5Hz","10Hz"] model: ["1Hz","2Hz","5Hz","10Hz","25Hz"]
enabled: repeatCheck.checked enabled: repeatCheck.checked
onActivated: {
var freq = 1;
switch(index) {
case 0: freq = 1; break;
case 1: freq = 2; break;
case 2: freq = 5; break;
case 3: freq = 10; break;
case 4: freq = 25; break;
}
_activeJoystick.setButtonFrequency(modelData, freq)
}
Component.onCompleted: {
}
} }
Item { Item {
width: ScreenTools.defaultFontPixelWidth * 2 width: ScreenTools.defaultFontPixelWidth * 2

Loading…
Cancel
Save