@@ -91,22 +91,31 @@ const float Joystick::_maxButtonFrequencyHz = 50.0f;
91
91
92
92
AssignedButtonAction::AssignedButtonAction (QObject* parent, const QString action)
93
93
: QObject(parent)
94
- , action(action)
94
+ , _action(action)
95
+ , _isPwmOverrideAction(false )
96
+ , _rcChannel(0 )
95
97
{
96
98
}
97
99
98
- AssignedButtonRcPwmOverrideAction::AssignedButtonRcPwmOverrideAction (
100
+ AssignedButtonAction::AssignedButtonAction (
99
101
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 )
101
105
, _loPwmValue(loPwmValue)
102
106
, _hiPwmValue(hiPwmValue)
103
107
, _latchMode(latch)
104
108
, _rcChannel(getRcChannelFromAction(action))
105
109
{
106
110
}
107
111
108
- void AssignedButtonRcPwmOverrideAction::send (Vehicle *vehicle, bool buttonDown)
112
+ void AssignedButtonAction::sendPwm (Vehicle *vehicle, bool buttonDown)
109
113
{
114
+ if (!_isPwmOverrideAction) {
115
+ qCWarning (JoystickLog) << " send called on non-pwm action" ;
116
+ return ;
117
+ }
118
+
110
119
uint16_t pwmValue = buttonDown ? _hiPwmValue : _loPwmValue;
111
120
if (_latchMode) {
112
121
qCDebug (JoystickLog) << " Latch mode, current saved button state " << (_latchButtonDown ? " down" : " up" );
@@ -124,22 +133,27 @@ void AssignedButtonRcPwmOverrideAction::send(Vehicle *vehicle, bool buttonDown)
124
133
vehicle->rcChannelOverride (_rcChannel, pwmValue);
125
134
}
126
135
127
- uint8_t AssignedButtonRcPwmOverrideAction::channel () const
136
+ uint8_t AssignedButtonAction::pwmChannel () const
128
137
{
129
138
return _rcChannel;
130
139
};
131
140
132
- void AssignedButtonRcPwmOverrideAction::setLatchMode (bool latch)
141
+ void AssignedButtonAction::pwmLatchMode (bool latch)
133
142
{
134
143
_latchMode = latch;
135
144
}
136
145
137
- bool AssignedButtonRcPwmOverrideAction::getLatchMode ()
146
+ bool AssignedButtonAction::pwmLatchMode () const
138
147
{
139
148
return _latchMode;
140
149
}
141
150
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)
143
157
{
144
158
QRegularExpression re (" ^Channel (\\ d{1,2}) direct PWM" );
145
159
QRegularExpressionMatch match = re.match (action);
@@ -357,10 +371,6 @@ void Joystick::_loadSettings()
357
371
// FunctionAxis mappings are always stored in TX mode 2
358
372
// Remap to stored TX mode in settings
359
373
_remapAxes (2 , _transmitterMode, _rgFunctionAxis);
360
- // TODO add with real channels
361
- // for (int channel = 8; channel <= 16; channel++) {
362
- // _rcOverrides.append(nullptr);
363
- // }
364
374
365
375
for (int button = 0 ; button < _totalButtonCount; button++) {
366
376
QString action = settings.value (QString (_buttonActionNameKey).arg (button), QString ()).toString ();
@@ -376,21 +386,16 @@ void Joystick::_loadSettings()
376
386
bool latch = settings.value (QString (_buttonActionLatchPwmValueKey).arg (button), false ).toBool ();
377
387
qCDebug (JoystickLog) << " _loadSettings button:action:pwm" << button << action << " L:" << lowPwm
378
388
<< " 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);
385
390
} else {
386
391
ap = new AssignedButtonAction (this , action);
387
- ap->repeat = settings.value (QString (_buttonActionRepeatKey).arg (button), false ).toBool ();
388
392
}
393
+ ap->repeat (settings.value (QString (_buttonActionRepeatKey).arg (button), false ).toBool ());
389
394
390
395
_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 () ;
394
399
395
400
}
396
401
}
@@ -408,11 +413,14 @@ void Joystick::_saveButtonSettings()
408
413
settings.beginGroup (_name);
409
414
for (int button = 0 ; button < _totalButtonCount; button++) {
410
415
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
+
416
424
}
417
425
}
418
426
}
@@ -570,7 +578,7 @@ void Joystick::run()
570
578
_axisTime.start ();
571
579
for (int buttonIndex = 0 ; buttonIndex < _totalButtonCount; buttonIndex++) {
572
580
if (_buttonActionArray[buttonIndex]) {
573
- _buttonActionArray[buttonIndex]->buttonTime .start ();
581
+ _buttonActionArray[buttonIndex]->buttonTime () .start ();
574
582
}
575
583
}
576
584
while (!_exitThread) {
@@ -621,18 +629,18 @@ void Joystick::_handleButtons()
621
629
for (int buttonIndex = 0 ; buttonIndex < _totalButtonCount; buttonIndex++) {
622
630
if (_rgButtonValues[buttonIndex] == BUTTON_DOWN || _rgButtonValues[buttonIndex] == BUTTON_REPEAT) {
623
631
if (_buttonActionArray[buttonIndex]) {
624
- QString buttonAction = _buttonActionArray[buttonIndex]->action ;
632
+ QString buttonAction = _buttonActionArray[buttonIndex]->action () ;
625
633
if (buttonAction.isEmpty () || buttonAction == _buttonActionNone)
626
634
continue ;
627
- if (!_buttonActionArray[buttonIndex]->repeat ) {
635
+ if (!_buttonActionArray[buttonIndex]->repeat () ) {
628
636
// -- This button just went down
629
637
if (_rgButtonValues[buttonIndex] == BUTTON_DOWN) {
630
638
// Check for a multi-button action
631
639
QList<int > rgButtons = { buttonIndex };
632
640
bool executeButtonAction = true ;
633
641
for (int multiIndex = 0 ; multiIndex < _totalButtonCount; multiIndex++) {
634
642
if (multiIndex != buttonIndex) {
635
- if (_buttonActionArray[multiIndex] && _buttonActionArray[multiIndex]->action == buttonAction) {
643
+ if (_buttonActionArray[multiIndex] && _buttonActionArray[multiIndex]->action () == buttonAction) {
636
644
// We found a multi-button action
637
645
if (_rgButtonValues[multiIndex] == BUTTON_DOWN || _rgButtonValues[multiIndex] == BUTTON_REPEAT) {
638
646
// So far so good
@@ -654,8 +662,8 @@ void Joystick::_handleButtons()
654
662
} else {
655
663
// -- Process repeat buttons
656
664
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 ();
659
667
qCDebug (JoystickLog) << " Repeat button triggered" << buttonIndex << buttonAction;
660
668
_executeButtonAction (buttonAction, buttonIndex, true );
661
669
}
@@ -668,7 +676,7 @@ void Joystick::_handleButtons()
668
676
if (buttonIndex < 256 ) {
669
677
if (lastBbuttonValues[buttonIndex] == BUTTON_DOWN || lastBbuttonValues[buttonIndex] == BUTTON_REPEAT) {
670
678
if (_buttonActionArray[buttonIndex]) {
671
- QString buttonAction = _buttonActionArray[buttonIndex]->action ;
679
+ QString buttonAction = _buttonActionArray[buttonIndex]->action () ;
672
680
if (buttonAction.isEmpty () || buttonAction == _buttonActionNone)
673
681
continue ;
674
682
qCDebug (JoystickLog) << " Button up" << buttonIndex << buttonAction;
@@ -881,21 +889,21 @@ void Joystick::setButtonRepeat(int button, bool repeat)
881
889
if (!_validButton (button) || !_buttonActionArray[button]) {
882
890
return ;
883
891
}
884
- _buttonActionArray[button]->repeat = repeat;
885
- _buttonActionArray[button]->buttonTime .start ();
892
+ _buttonActionArray[button]->repeat ( repeat) ;
893
+ _buttonActionArray[button]->buttonTime () .start ();
886
894
// -- Save to settings
887
895
QSettings settings;
888
896
settings.beginGroup (_settingsGroup);
889
897
settings.beginGroup (_name);
890
- settings.setValue (QString (_buttonActionRepeatKey).arg (button), _buttonActionArray[button]->repeat );
898
+ settings.setValue (QString (_buttonActionRepeatKey).arg (button), _buttonActionArray[button]->repeat () );
891
899
}
892
900
893
901
bool Joystick::getButtonRepeat (int button)
894
902
{
895
903
if (!_validButton (button) || !_buttonActionArray[button]) {
896
904
return false ;
897
905
}
898
- return _buttonActionArray[button]->repeat ;
906
+ return _buttonActionArray[button]->repeat () ;
899
907
}
900
908
901
909
void Joystick::setButtonAction (int button, const QString& action)
@@ -909,20 +917,24 @@ void Joystick::setButtonAction(int button, const QString& action)
909
917
settings.beginGroup (_name);
910
918
if (action.isEmpty () || action == _buttonActionNone) {
911
919
if (_buttonActionArray[button]) {
912
- _buttonActionArray[button]->deleteLater ();
913
- _buttonActionArray[button] = nullptr ;
914
920
// -- Clear from settings
915
- // TODO clear if PWM type
916
921
settings.remove (QString (_buttonActionNameKey).arg (button));
917
922
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 ;
918
930
}
919
931
} else {
920
932
bool isPwmAction = assignableActionIsPwm (action);
921
933
AssignedButtonAction *ap;
922
934
923
935
if (!_buttonActionArray[button]) {
924
936
if (isPwmAction) {
925
- ap = new AssignedButtonRcPwmOverrideAction (this , action, 0 , 0 , false );
937
+ ap = new AssignedButtonAction (this , action, 0 , 0 , false );
926
938
} else {
927
939
ap = new AssignedButtonAction (this , action);
928
940
}
@@ -931,23 +943,28 @@ void Joystick::setButtonAction(int button, const QString& action)
931
943
if (isPwmAction) {
932
944
// TODO fix it better, maybe one aciton with PWM values in it
933
945
_buttonActionArray[button]->deleteLater ();
934
- ap = new AssignedButtonRcPwmOverrideAction (this , action, 0 , 0 , false );
946
+ ap = new AssignedButtonAction (this , action, 0 , 0 , false );
935
947
_buttonActionArray[button] = ap;
936
948
}
937
- _buttonActionArray[button]->action = action;
949
+ _buttonActionArray[button]->action ( action) ;
938
950
}
939
951
// -- Make sure repeat is off if this action doesn't support repeats
940
952
int idx = _findAssignableButtonAction (action);
941
953
if (idx >= 0 ) {
942
954
AssignableButtonAction* p = qobject_cast<AssignableButtonAction*>(_assignableButtonActions[idx]);
943
955
if (!p->canRepeat ()) {
944
- _buttonActionArray[button]->repeat = false ;
956
+ _buttonActionArray[button]->repeat ( false ) ;
945
957
}
946
958
}
947
959
948
960
// -- 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
+ }
951
968
}
952
969
emit buttonActionsChanged ();
953
970
}
@@ -956,7 +973,7 @@ QString Joystick::getButtonAction(int button)
956
973
{
957
974
if (_validButton (button)) {
958
975
if (_buttonActionArray[button]) {
959
- return _buttonActionArray[button]->action ;
976
+ return _buttonActionArray[button]->action () ;
960
977
}
961
978
}
962
979
return QString (_buttonActionNone);
@@ -977,6 +994,7 @@ bool Joystick::assignableActionIsPwm(QString action) {
977
994
}
978
995
979
996
void Joystick::setButtonPwm (int button, bool lowPwm, int value) {
997
+ // TODO czy tutaj przychodzi z GUI i trzeba ustawic tez w _buttonActionArray[button]?
980
998
qDebug (JoystickLog) << " setButtonPwm: " << button << (lowPwm ? " LOW " : " HIGH " ) << value;
981
999
if (_validButton (button)) {
982
1000
if (assignableActionIsPwm (button)) {
@@ -996,8 +1014,6 @@ int Joystick::getButtonPwm(int button, bool lowPwm) {
996
1014
qDebug (JoystickLog) << " getButtonPwm: " << button << (lowPwm ? " LOW " : " HIGH " );
997
1015
if (_validButton (button)) {
998
1016
if (assignableActionIsPwm (button)) {
999
- // const AssignedButtonRcPwmOverrideAction *ap = dynamic_cast<const AssignedButtonRcPwmOverrideAction *>(_buttonActionArray[button]);
1000
- // int rc = ap->channel();
1001
1017
QSettings settings;
1002
1018
settings.beginGroup (_settingsGroup);
1003
1019
settings.beginGroup (_name);
@@ -1018,25 +1034,24 @@ void Joystick::setButtonPwmLatch(int button, bool latch)
1018
1034
}
1019
1035
qCDebug (JoystickLog) << " PWM Latch mode for button " << button << (latch ? " enabled" : " disabled" );
1020
1036
// 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);
1023
1039
1024
1040
// TODO finish saving settings
1025
- /*
1041
+
1026
1042
QSettings settings;
1027
1043
settings.beginGroup (_settingsGroup);
1028
1044
settings.beginGroup (_name);
1029
- settings.setValue(QString(_buttonActionRepeatKey).arg(button), _buttonActionArray[button]->repeat);
1030
- */
1045
+ settings.setValue (QString (_buttonActionLatchPwmValueKey).arg (button), action->pwmLatchMode ());
1031
1046
}
1032
1047
1033
1048
bool Joystick::getButtonPwmLatch (int button) {
1034
1049
if (!_validButton (button) || !_buttonActionArray[button]) {
1035
1050
return false ;
1036
1051
}
1037
1052
// 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 ();
1040
1055
}
1041
1056
1042
1057
QStringList Joystick::buttonActions ()
@@ -1330,6 +1345,7 @@ void Joystick::_buildActionList(Vehicle* activeVehicle)
1330
1345
_assignableButtonActions.append (new AssignableButtonAction (this , _buttonActionGripperGrab));
1331
1346
_assignableButtonActions.append (new AssignableButtonAction (this , _buttonActionGripperRelease));
1332
1347
1348
+ // TODO(bzd) take channel nos from config, especially max
1333
1349
for (int ch = 8 ; ch <= 16 ;ch++) {
1334
1350
_assignableButtonActions.append (new AssignableButtonAction (this , QString (" Channel %1 direct PWM" ).arg (ch)));
1335
1351
}
@@ -1349,23 +1365,8 @@ void Joystick::_buildActionList(Vehicle* activeVehicle)
1349
1365
bool Joystick::_executeRcOverrideButtonAction (int buttonIndex, bool buttonDown)
1350
1366
{
1351
1367
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 ;
1355
1370
}
1356
1371
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;*/
1371
1372
}
0 commit comments