Skip to content

Commit b44de62

Browse files
committed
Refactor PWM override to single joystick action class
1 parent 1b7ca68 commit b44de62

File tree

3 files changed

+98
-92
lines changed

3 files changed

+98
-92
lines changed

src/Joystick/Joystick.cc

Lines changed: 75 additions & 74 deletions
Original file line numberDiff line numberDiff line change
@@ -91,22 +91,31 @@ const float Joystick::_maxButtonFrequencyHz = 50.0f;
9191

9292
AssignedButtonAction::AssignedButtonAction(QObject* parent, const QString action)
9393
: QObject(parent)
94-
, action(action)
94+
, _action(action)
95+
, _isPwmOverrideAction(false)
96+
, _rcChannel(0)
9597
{
9698
}
9799

98-
AssignedButtonRcPwmOverrideAction::AssignedButtonRcPwmOverrideAction(
100+
AssignedButtonAction::AssignedButtonAction(
99101
QObject *parent, const QString action, const uint16_t loPwmValue, const uint16_t hiPwmValue, bool latch)
100-
: AssignedButtonAction(parent, action)
102+
: QObject(parent)
103+
, _action(action)
104+
, _isPwmOverrideAction(true)
101105
, _loPwmValue(loPwmValue)
102106
, _hiPwmValue(hiPwmValue)
103107
, _latchMode(latch)
104108
, _rcChannel(getRcChannelFromAction(action))
105109
{
106110
}
107111

108-
void AssignedButtonRcPwmOverrideAction::send(Vehicle *vehicle, bool buttonDown)
112+
void AssignedButtonAction::sendPwm(Vehicle *vehicle, bool buttonDown)
109113
{
114+
if (!_isPwmOverrideAction) {
115+
qCWarning(JoystickLog) << "send called on non-pwm action";
116+
return;
117+
}
118+
110119
uint16_t pwmValue = buttonDown ? _hiPwmValue : _loPwmValue;
111120
if (_latchMode) {
112121
qCDebug(JoystickLog) << "Latch mode, current saved button state " << (_latchButtonDown ? "down" : "up");
@@ -124,22 +133,27 @@ void AssignedButtonRcPwmOverrideAction::send(Vehicle *vehicle, bool buttonDown)
124133
vehicle->rcChannelOverride(_rcChannel, pwmValue);
125134
}
126135

127-
uint8_t AssignedButtonRcPwmOverrideAction::channel() const
136+
uint8_t AssignedButtonAction::pwmChannel() const
128137
{
129138
return _rcChannel;
130139
};
131140

132-
void AssignedButtonRcPwmOverrideAction::setLatchMode(bool latch)
141+
void AssignedButtonAction::pwmLatchMode(bool latch)
133142
{
134143
_latchMode = latch;
135144
}
136145

137-
bool AssignedButtonRcPwmOverrideAction::getLatchMode()
146+
bool AssignedButtonAction::pwmLatchMode() const
138147
{
139148
return _latchMode;
140149
}
141150

142-
uint8_t AssignedButtonRcPwmOverrideAction::getRcChannelFromAction(const QString action)
151+
bool AssignedButtonAction::isPwmOverrideAction() const
152+
{
153+
return _isPwmOverrideAction;
154+
}
155+
156+
uint8_t AssignedButtonAction::getRcChannelFromAction(const QString action)
143157
{
144158
QRegularExpression re("^Channel (\\d{1,2}) direct PWM");
145159
QRegularExpressionMatch match = re.match(action);
@@ -357,10 +371,6 @@ void Joystick::_loadSettings()
357371
// FunctionAxis mappings are always stored in TX mode 2
358372
// Remap to stored TX mode in settings
359373
_remapAxes(2, _transmitterMode, _rgFunctionAxis);
360-
//TODO add with real channels
361-
// for (int channel = 8; channel <= 16; channel++) {
362-
// _rcOverrides.append(nullptr);
363-
// }
364374

365375
for (int button = 0; button < _totalButtonCount; button++) {
366376
QString action = settings.value(QString(_buttonActionNameKey).arg(button), QString()).toString();
@@ -376,21 +386,16 @@ void Joystick::_loadSettings()
376386
bool latch = settings.value(QString(_buttonActionLatchPwmValueKey).arg(button), false).toBool();
377387
qCDebug(JoystickLog) << "_loadSettings button:action:pwm" << button << action << "L:" << lowPwm
378388
<< " H:" << highPwm << " Latch:" << latch;
379-
// int idx = channel - 8;
380-
// if (_rcOverrides[idx]) {
381-
// delete _rcOverrides[idx];
382-
// }
383-
ap = new AssignedButtonRcPwmOverrideAction(this, action, lowPwm, highPwm, false);
384-
//.append(JoystickRcOverride(channel, lowPwm, highPwm, latch));
389+
ap = new AssignedButtonAction(this, action, lowPwm, highPwm, latch);
385390
} else {
386391
ap = new AssignedButtonAction(this, action);
387-
ap->repeat = settings.value(QString(_buttonActionRepeatKey).arg(button), false).toBool();
388392
}
393+
ap->repeat(settings.value(QString(_buttonActionRepeatKey).arg(button), false).toBool());
389394

390395
_buttonActionArray[button] = ap;
391-
_buttonActionArray[button]->buttonTime.start();
392-
qCDebug(JoystickLog) << "_loadSettings button:action" << button << _buttonActionArray[button]->action
393-
<< _buttonActionArray[button]->repeat;
396+
_buttonActionArray[button]->buttonTime().start();
397+
qCDebug(JoystickLog) << "_loadSettings button:action" << button << _buttonActionArray[button]->action()
398+
<< _buttonActionArray[button]->repeat();
394399

395400
}
396401
}
@@ -408,11 +413,14 @@ void Joystick::_saveButtonSettings()
408413
settings.beginGroup(_name);
409414
for (int button = 0; button < _totalButtonCount; button++) {
410415
if(_buttonActionArray[button]) {
411-
settings.setValue(QString(_buttonActionNameKey).arg(button), _buttonActionArray[button]->action);
412-
settings.setValue(QString(_buttonActionRepeatKey).arg(button), _buttonActionArray[button]->repeat);
413-
qCDebug(JoystickLog) << "_saveButtonSettings button:action" << button << _buttonActionArray[button]->action << _buttonActionArray[button]->repeat;
414-
if (assignableActionIsPwm(button)) {
415-
//TODO finish, but low priority
416+
settings.setValue(QString(_buttonActionNameKey).arg(button), _buttonActionArray[button]->action());
417+
settings.setValue(QString(_buttonActionRepeatKey).arg(button), _buttonActionArray[button]->repeat());
418+
qCDebug(JoystickLog) << "_saveButtonSettings button:action" << button << _buttonActionArray[button]->action() << _buttonActionArray[button]->repeat();
419+
if (_buttonActionArray[button]->isPwmOverrideAction()) {
420+
settings.setValue(QString(_buttonActionLowPwmValueKey).arg(button), _buttonActionArray[button]->lowPwm());
421+
settings.setValue(QString(_buttonActionHighPwmValueKey).arg(button), _buttonActionArray[button]->highPwm());
422+
settings.setValue(QString(_buttonActionLatchPwmValueKey).arg(button), _buttonActionArray[button]->pwmLatchMode());
423+
416424
}
417425
}
418426
}
@@ -570,7 +578,7 @@ void Joystick::run()
570578
_axisTime.start();
571579
for (int buttonIndex = 0; buttonIndex < _totalButtonCount; buttonIndex++) {
572580
if(_buttonActionArray[buttonIndex]) {
573-
_buttonActionArray[buttonIndex]->buttonTime.start();
581+
_buttonActionArray[buttonIndex]->buttonTime().start();
574582
}
575583
}
576584
while (!_exitThread) {
@@ -621,18 +629,18 @@ void Joystick::_handleButtons()
621629
for (int buttonIndex = 0; buttonIndex < _totalButtonCount; buttonIndex++) {
622630
if(_rgButtonValues[buttonIndex] == BUTTON_DOWN || _rgButtonValues[buttonIndex] == BUTTON_REPEAT) {
623631
if(_buttonActionArray[buttonIndex]) {
624-
QString buttonAction = _buttonActionArray[buttonIndex]->action;
632+
QString buttonAction = _buttonActionArray[buttonIndex]->action();
625633
if(buttonAction.isEmpty() || buttonAction == _buttonActionNone)
626634
continue;
627-
if(!_buttonActionArray[buttonIndex]->repeat) {
635+
if(!_buttonActionArray[buttonIndex]->repeat()) {
628636
//-- This button just went down
629637
if(_rgButtonValues[buttonIndex] == BUTTON_DOWN) {
630638
// Check for a multi-button action
631639
QList<int> rgButtons = { buttonIndex };
632640
bool executeButtonAction = true;
633641
for (int multiIndex = 0; multiIndex < _totalButtonCount; multiIndex++) {
634642
if (multiIndex != buttonIndex) {
635-
if (_buttonActionArray[multiIndex] && _buttonActionArray[multiIndex]->action == buttonAction) {
643+
if (_buttonActionArray[multiIndex] && _buttonActionArray[multiIndex]->action() == buttonAction) {
636644
// We found a multi-button action
637645
if (_rgButtonValues[multiIndex] == BUTTON_DOWN || _rgButtonValues[multiIndex] == BUTTON_REPEAT) {
638646
// So far so good
@@ -654,8 +662,8 @@ void Joystick::_handleButtons()
654662
} else {
655663
//-- Process repeat buttons
656664
int buttonDelay = static_cast<int>(1000.0f / _buttonFrequencyHz);
657-
if(_buttonActionArray[buttonIndex]->buttonTime.elapsed() > buttonDelay) {
658-
_buttonActionArray[buttonIndex]->buttonTime.start();
665+
if(_buttonActionArray[buttonIndex]->buttonTime().elapsed() > buttonDelay) {
666+
_buttonActionArray[buttonIndex]->buttonTime().start();
659667
qCDebug(JoystickLog) << "Repeat button triggered" << buttonIndex << buttonAction;
660668
_executeButtonAction(buttonAction, buttonIndex, true);
661669
}
@@ -668,7 +676,7 @@ void Joystick::_handleButtons()
668676
if(buttonIndex < 256) {
669677
if(lastBbuttonValues[buttonIndex] == BUTTON_DOWN || lastBbuttonValues[buttonIndex] == BUTTON_REPEAT) {
670678
if(_buttonActionArray[buttonIndex]) {
671-
QString buttonAction = _buttonActionArray[buttonIndex]->action;
679+
QString buttonAction = _buttonActionArray[buttonIndex]->action();
672680
if(buttonAction.isEmpty() || buttonAction == _buttonActionNone)
673681
continue;
674682
qCDebug(JoystickLog) << "Button up" << buttonIndex << buttonAction;
@@ -881,21 +889,21 @@ void Joystick::setButtonRepeat(int button, bool repeat)
881889
if (!_validButton(button) || !_buttonActionArray[button]) {
882890
return;
883891
}
884-
_buttonActionArray[button]->repeat = repeat;
885-
_buttonActionArray[button]->buttonTime.start();
892+
_buttonActionArray[button]->repeat(repeat);
893+
_buttonActionArray[button]->buttonTime().start();
886894
//-- Save to settings
887895
QSettings settings;
888896
settings.beginGroup(_settingsGroup);
889897
settings.beginGroup(_name);
890-
settings.setValue(QString(_buttonActionRepeatKey).arg(button), _buttonActionArray[button]->repeat);
898+
settings.setValue(QString(_buttonActionRepeatKey).arg(button), _buttonActionArray[button]->repeat());
891899
}
892900

893901
bool Joystick::getButtonRepeat(int button)
894902
{
895903
if (!_validButton(button) || !_buttonActionArray[button]) {
896904
return false;
897905
}
898-
return _buttonActionArray[button]->repeat;
906+
return _buttonActionArray[button]->repeat();
899907
}
900908

901909
void Joystick::setButtonAction(int button, const QString& action)
@@ -909,20 +917,24 @@ void Joystick::setButtonAction(int button, const QString& action)
909917
settings.beginGroup(_name);
910918
if(action.isEmpty() || action == _buttonActionNone) {
911919
if(_buttonActionArray[button]) {
912-
_buttonActionArray[button]->deleteLater();
913-
_buttonActionArray[button] = nullptr;
914920
//-- Clear from settings
915-
//TODO clear if PWM type
916921
settings.remove(QString(_buttonActionNameKey).arg(button));
917922
settings.remove(QString(_buttonActionRepeatKey).arg(button));
923+
if (_buttonActionArray[button]->isPwmOverrideAction()) {
924+
settings.remove(QString(_buttonActionHighPwmValueKey).arg(button));
925+
settings.remove(QString(_buttonActionLowPwmValueKey).arg(button));
926+
settings.remove(QString(_buttonActionLatchPwmValueKey).arg(button));
927+
}
928+
_buttonActionArray[button]->deleteLater();
929+
_buttonActionArray[button] = nullptr;
918930
}
919931
} else {
920932
bool isPwmAction = assignableActionIsPwm(action);
921933
AssignedButtonAction *ap;
922934

923935
if(!_buttonActionArray[button]) {
924936
if (isPwmAction) {
925-
ap = new AssignedButtonRcPwmOverrideAction(this, action, 0, 0, false);
937+
ap = new AssignedButtonAction(this, action, 0, 0, false);
926938
} else {
927939
ap = new AssignedButtonAction(this, action);
928940
}
@@ -931,23 +943,28 @@ void Joystick::setButtonAction(int button, const QString& action)
931943
if (isPwmAction) {
932944
//TODO fix it better, maybe one aciton with PWM values in it
933945
_buttonActionArray[button]->deleteLater();
934-
ap = new AssignedButtonRcPwmOverrideAction(this, action, 0, 0, false);
946+
ap = new AssignedButtonAction(this, action, 0, 0, false);
935947
_buttonActionArray[button] = ap;
936948
}
937-
_buttonActionArray[button]->action = action;
949+
_buttonActionArray[button]->action(action);
938950
}
939951
//-- Make sure repeat is off if this action doesn't support repeats
940952
int idx = _findAssignableButtonAction(action);
941953
if(idx >= 0) {
942954
AssignableButtonAction* p = qobject_cast<AssignableButtonAction*>(_assignableButtonActions[idx]);
943955
if(!p->canRepeat()) {
944-
_buttonActionArray[button]->repeat = false;
956+
_buttonActionArray[button]->repeat(false);
945957
}
946958
}
947959

948960
//-- Save to settings
949-
settings.setValue(QString(_buttonActionNameKey).arg(button), _buttonActionArray[button]->action);
950-
settings.setValue(QString(_buttonActionRepeatKey).arg(button), _buttonActionArray[button]->repeat);
961+
settings.setValue(QString(_buttonActionNameKey).arg(button), _buttonActionArray[button]->action());
962+
settings.setValue(QString(_buttonActionRepeatKey).arg(button), _buttonActionArray[button]->repeat());
963+
if (isPwmAction) {
964+
settings.setValue(QString(_buttonActionLowPwmValueKey).arg(button), _buttonActionArray[button]->lowPwm());
965+
settings.setValue(QString(_buttonActionHighPwmValueKey).arg(button), _buttonActionArray[button]->highPwm());
966+
settings.setValue(QString(_buttonActionLatchPwmValueKey).arg(button), _buttonActionArray[button]->pwmLatchMode());
967+
}
951968
}
952969
emit buttonActionsChanged();
953970
}
@@ -956,7 +973,7 @@ QString Joystick::getButtonAction(int button)
956973
{
957974
if (_validButton(button)) {
958975
if(_buttonActionArray[button]) {
959-
return _buttonActionArray[button]->action;
976+
return _buttonActionArray[button]->action();
960977
}
961978
}
962979
return QString(_buttonActionNone);
@@ -977,6 +994,7 @@ bool Joystick::assignableActionIsPwm(QString action) {
977994
}
978995

979996
void Joystick::setButtonPwm(int button, bool lowPwm, int value) {
997+
//TODO czy tutaj przychodzi z GUI i trzeba ustawic tez w _buttonActionArray[button]?
980998
qDebug(JoystickLog) << "setButtonPwm: " << button << (lowPwm ? "LOW " : "HIGH ") << value;
981999
if (_validButton(button)) {
9821000
if (assignableActionIsPwm(button)) {
@@ -996,8 +1014,6 @@ int Joystick::getButtonPwm(int button, bool lowPwm) {
9961014
qDebug(JoystickLog) << "getButtonPwm: " << button << (lowPwm ? "LOW " : "HIGH ");
9971015
if (_validButton(button)) {
9981016
if (assignableActionIsPwm(button)) {
999-
// const AssignedButtonRcPwmOverrideAction *ap = dynamic_cast<const AssignedButtonRcPwmOverrideAction *>(_buttonActionArray[button]);
1000-
// int rc = ap->channel();
10011017
QSettings settings;
10021018
settings.beginGroup(_settingsGroup);
10031019
settings.beginGroup(_name);
@@ -1018,25 +1034,24 @@ void Joystick::setButtonPwmLatch(int button, bool latch)
10181034
}
10191035
qCDebug(JoystickLog) << "PWM Latch mode for button " << button << (latch ? " enabled" : " disabled");
10201036
//TODO check is really this class
1021-
AssignedButtonRcPwmOverrideAction *action = dynamic_cast<AssignedButtonRcPwmOverrideAction *>(_buttonActionArray[button]);
1022-
action->setLatchMode(latch);
1037+
auto *action = (_buttonActionArray[button]);
1038+
action->pwmLatchMode(latch);
10231039

10241040
//TODO finish saving settings
1025-
/*
1041+
10261042
QSettings settings;
10271043
settings.beginGroup(_settingsGroup);
10281044
settings.beginGroup(_name);
1029-
settings.setValue(QString(_buttonActionRepeatKey).arg(button), _buttonActionArray[button]->repeat);
1030-
*/
1045+
settings.setValue(QString(_buttonActionLatchPwmValueKey).arg(button), action->pwmLatchMode());
10311046
}
10321047

10331048
bool Joystick::getButtonPwmLatch(int button) {
10341049
if (!_validButton(button) || !_buttonActionArray[button]) {
10351050
return false;
10361051
}
10371052
//TODO check is really this class
1038-
AssignedButtonRcPwmOverrideAction *action = dynamic_cast<AssignedButtonRcPwmOverrideAction *>(_buttonActionArray[button]);
1039-
return action->getLatchMode();
1053+
auto *action = (_buttonActionArray[button]);
1054+
return action->pwmLatchMode();
10401055
}
10411056

10421057
QStringList Joystick::buttonActions()
@@ -1330,6 +1345,7 @@ void Joystick::_buildActionList(Vehicle* activeVehicle)
13301345
_assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionGripperGrab));
13311346
_assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionGripperRelease));
13321347

1348+
// TODO(bzd) take channel nos from config, especially max
13331349
for (int ch = 8; ch <= 16;ch++) {
13341350
_assignableButtonActions.append(new AssignableButtonAction(this, QString("Channel %1 direct PWM").arg(ch)));
13351351
}
@@ -1349,23 +1365,8 @@ void Joystick::_buildActionList(Vehicle* activeVehicle)
13491365
bool Joystick::_executeRcOverrideButtonAction(int buttonIndex, bool buttonDown)
13501366
{
13511367
if (_buttonActionArray[buttonIndex]) {
1352-
AssignedButtonRcPwmOverrideAction* buttonAction =
1353-
dynamic_cast<AssignedButtonRcPwmOverrideAction *>(_buttonActionArray[buttonIndex]);
1354-
buttonAction->send(_activeVehicle, buttonDown);
1368+
_buttonActionArray[buttonIndex]->sendPwm(_activeVehicle, buttonDown);
1369+
return true;
13551370
}
13561371
return false;
1357-
/* int channelNo = getRcChannelFromAction(action);
1358-
if (channelNo == -1) {
1359-
return false;
1360-
}
1361-
qCDebug(JoystickLog) << "RC override matched for channel " << channelNo;
1362-
//TODO make a map rcChannel : override (ev null if not set)
1363-
for (auto& item : _rcOverrides) {
1364-
if (channelNo == item->channel()) {
1365-
qCDebug(JoystickLog) << "Sending RC override " << channelNo;
1366-
item->send(_activeVehicle, buttonDown);
1367-
return true;
1368-
}
1369-
}
1370-
return false;*/
13711372
}

0 commit comments

Comments
 (0)