10
10
11
11
#include " Joystick.h"
12
12
#include " QGC.h"
13
- #include " AutoPilotPlugin.h"
14
13
#include " UAS.h"
15
14
#include " QGCApplication.h"
16
15
#include " VideoManager.h"
@@ -88,6 +87,7 @@ const float Joystick::_minAxisFrequencyHz = 0.25f;
88
87
const float Joystick::_maxAxisFrequencyHz = 200 .0f ;
89
88
const float Joystick::_minButtonFrequencyHz = 0 .25f ;
90
89
const float Joystick::_maxButtonFrequencyHz = 50 .0f ;
90
+ const float Joystick::_rcOverrideFrequencyHz = 0 .5f ;
91
91
92
92
AssignedButtonAction::AssignedButtonAction (QObject* parent, const QString action)
93
93
: QObject(parent)
@@ -109,28 +109,28 @@ AssignedButtonAction::AssignedButtonAction(
109
109
{
110
110
}
111
111
112
- void AssignedButtonAction::sendPwm (Vehicle *vehicle, bool buttonDown)
112
+ int16_t AssignedButtonAction::calculatePwm (Vehicle *vehicle, bool buttonDown)
113
113
{
114
114
if (!_isPwmOverrideAction) {
115
115
qCWarning (JoystickLog) << " send called on non-pwm action" ;
116
- return ;
116
+ return - 1 ;
117
117
}
118
118
119
119
uint16_t pwmValue = buttonDown ? _hiPwmValue : _loPwmValue;
120
120
if (_pwmLatchMode) {
121
121
qCDebug (JoystickLog) << " Latch mode, current saved button state " << (_pwmLatchButtonDown ? " down" : " up" );
122
122
123
123
if (buttonDown) {
124
+ // altering latch state
124
125
_pwmLatchButtonDown = !_pwmLatchButtonDown;
125
- pwmValue = _pwmLatchButtonDown ? _hiPwmValue : _loPwmValue;
126
- } else {
127
- qCDebug (JoystickLog) << " since button is up - exiting" ;
128
- return ;
129
126
}
127
+ pwmValue = _pwmLatchButtonDown ? _hiPwmValue : _loPwmValue;
130
128
}
131
129
132
- qCDebug (JoystickLog) << " Sending PWM Value " << pwmValue;
133
- vehicle->rcChannelOverride (_pwmRcChannel, pwmValue);
130
+ qCDebug (JoystickLog) << " Calculated PWM Value " << pwmValue << " for action " << _action;
131
+ // vehicle->rcChannelOverride(_pwmRcChannel, pwmValue);
132
+
133
+ return pwmValue;
134
134
}
135
135
136
136
uint8_t AssignedButtonAction::getRcChannelFromAction (const QString action)
@@ -162,11 +162,8 @@ Joystick::Joystick(const QString& name, int axisCount, int buttonCount, int hatC
162
162
, _totalButtonCount(_buttonCount+_hatButtonCount)
163
163
, _multiVehicleManager(multiVehicleManager)
164
164
{
165
- <<<<<<< HEAD
166
165
qRegisterMetaType<GRIPPER_ACTIONS>();
167
166
168
- =======
169
- >>>>>>> Refactor for clearness
170
167
_rgAxisValues = new int [static_cast <size_t >(_axisCount)];
171
168
_rgCalibration = new Calibration_t[static_cast <size_t >(_axisCount)];
172
169
_rgButtonValues = new uint8_t [static_cast <size_t >(_totalButtonCount)];
@@ -177,6 +174,7 @@ Joystick::Joystick(const QString& name, int axisCount, int buttonCount, int hatC
177
174
_rgButtonValues[i] = BUTTON_UP;
178
175
_buttonActionArray.append (nullptr );
179
176
}
177
+
180
178
_buildActionList (_multiVehicleManager->activeVehicle ());
181
179
_updateTXModeSettingsKey (_multiVehicleManager->activeVehicle ());
182
180
_loadSettings ();
@@ -277,6 +275,7 @@ void Joystick::_activeVehicleChanged(Vehicle* activeVehicle)
277
275
int mode = settings.value (_txModeSettingsKey, activeVehicle->firmwarePlugin ()->defaultJoystickTXMode ()).toInt ();
278
276
setTXMode (mode);
279
277
}
278
+ _clearRcOverrideButtonActions ();
280
279
}
281
280
282
281
void Joystick::_loadSettings ()
@@ -384,7 +383,7 @@ void Joystick::_loadSettings()
384
383
_buttonActionArray[button]->buttonTime ().start ();
385
384
386
385
bool savedRepeatState = settings.value (QString (_buttonActionRepeatKey).arg (button), false ).toBool ();
387
- setButtonRepeatIfAvailable (button, savedRepeatState);
386
+ _setButtonRepeatIfAvailable (button, savedRepeatState);
388
387
389
388
qCDebug (JoystickLog) << " _loadSettings button:action" << button << _buttonActionArray[button]->action ()
390
389
<< _buttonActionArray[button]->repeat ();
@@ -411,7 +410,6 @@ void Joystick::_saveButtonSettings()
411
410
settings.setValue (QString (_buttonActionLowPwmValueKey).arg (button), _buttonActionArray[button]->lowPwm ());
412
411
settings.setValue (QString (_buttonActionHighPwmValueKey).arg (button), _buttonActionArray[button]->highPwm ());
413
412
settings.setValue (QString (_buttonActionLatchPwmValueKey).arg (button), _buttonActionArray[button]->pwmLatchMode ());
414
-
415
413
}
416
414
}
417
415
}
@@ -567,6 +565,7 @@ void Joystick::run()
567
565
_open ();
568
566
// -- Reset timers
569
567
_axisTime.start ();
568
+ _rcOverrideTimer.start ();
570
569
for (int buttonIndex = 0 ; buttonIndex < _totalButtonCount; buttonIndex++) {
571
570
if (_buttonActionArray[buttonIndex]) {
572
571
_buttonActionArray[buttonIndex]->buttonTime ().start ();
@@ -576,6 +575,7 @@ void Joystick::run()
576
575
_update ();
577
576
_handleButtons ();
578
577
_handleAxis ();
578
+ _handleRcOverride ();
579
579
QGC::SLEEP::msleep (qMin (static_cast <int >(1000 .0f / _maxAxisFrequencyHz), static_cast <int >(1000 .0f / _maxButtonFrequencyHz)) / 2 );
580
580
}
581
581
_close ();
@@ -775,6 +775,26 @@ void Joystick::_handleAxis()
775
775
}
776
776
}
777
777
778
+ void Joystick::_handleRcOverride ()
779
+ {
780
+ if (!_activeVehicle || !_activeVehicle->supportsRcChannelOverride ()) {
781
+ return ;
782
+ }
783
+ const int rcOverrideInterval = static_cast <int >(1000 .0f / _rcOverrideFrequencyHz);
784
+
785
+ if (_rcOverrideActive || _rcOverrideTimer.elapsed () > rcOverrideInterval) {
786
+ _rcOverrideActive = false ;
787
+ _rcOverrideTimer.start ();
788
+ uint16_t overrideData[18 ] = {UINT16_MAX};
789
+ overrideData[16 ] = _mapRcOverrideToRelease (17 , 0 );
790
+ overrideData[17 ] = _mapRcOverrideToRelease (18 , 0 );
791
+ for (int i = 0 ; i < MAX_RC_CHANNELS; i++) {
792
+ overrideData[i] = _rcOverride[i] == -1 ? _mapRcOverrideToRelease (i + 1 , 0 ) : _rcOverride[i];
793
+ }
794
+ _activeVehicle->rcChannelsOverride (overrideData);
795
+ }
796
+ }
797
+
778
798
void Joystick::startPolling (Vehicle* vehicle)
779
799
{
780
800
if (vehicle) {
@@ -907,7 +927,7 @@ void Joystick::setButtonAction(int button, const QString& action)
907
927
if (action.isEmpty () || action == _buttonActionNone) {
908
928
_pwmSettingsVisibilities[button] = false ;
909
929
if (_buttonActionArray[button]) {
910
- removeButtonSettings (button);
930
+ _removeButtonSettings (button);
911
931
_buttonActionArray[button]->deleteLater ();
912
932
_buttonActionArray[button] = nullptr ;
913
933
}
@@ -917,7 +937,7 @@ void Joystick::setButtonAction(int button, const QString& action)
917
937
qCDebug (JoystickLog) << " setButtonAction: isPwmAction " << isPwmAction;
918
938
919
939
if (!_buttonActionArray[button]) {
920
- _buttonActionArray[button] = isPwmAction ? new AssignedButtonAction (this , action, 1000 , 2000 , false )
940
+ _buttonActionArray[button] = isPwmAction ? new AssignedButtonAction (this , action, 1500 , 1500 , false )
921
941
: new AssignedButtonAction (this , action);
922
942
} else {
923
943
if (isPwmAction) {
@@ -935,14 +955,14 @@ void Joystick::setButtonAction(int button, const QString& action)
935
955
}
936
956
937
957
// -- Make sure repeat is off if this action doesn't support repeats
938
- setButtonRepeatIfAvailable (button, false );
939
- saveButtonSettings (button);
958
+ _setButtonRepeatIfAvailable (button, false );
959
+ _saveButtonSettings (button);
940
960
}
941
961
emit pwmVisibilitiesChanged ();
942
962
emit buttonActionsChanged ();
943
963
}
944
964
945
- void Joystick::setButtonRepeatIfAvailable (int button, bool repeat)
965
+ void Joystick::_setButtonRepeatIfAvailable (int button, bool repeat)
946
966
{
947
967
int idx = _findAssignableButtonAction (_buttonActionArray[button]->action ());
948
968
if (idx >= 0 ) {
@@ -955,7 +975,7 @@ void Joystick::setButtonRepeatIfAvailable(int button, bool repeat)
955
975
_buttonActionArray[button]->repeat (false );
956
976
}
957
977
958
- void Joystick::saveButtonSettings (int button)
978
+ void Joystick::_saveButtonSettings (int button)
959
979
{
960
980
QSettings settings;
961
981
settings.beginGroup (_settingsGroup);
@@ -970,7 +990,7 @@ void Joystick::saveButtonSettings(int button)
970
990
}
971
991
}
972
992
973
- void Joystick::removeButtonSettings (int button)
993
+ void Joystick::_removeButtonSettings (int button)
974
994
{
975
995
QSettings settings;
976
996
settings.beginGroup (_settingsGroup);
@@ -1349,10 +1369,10 @@ void Joystick::_buildActionList(Vehicle* activeVehicle)
1349
1369
_assignableButtonActions.append (new AssignableButtonAction (this , _buttonActionGripperGrab));
1350
1370
_assignableButtonActions.append (new AssignableButtonAction (this , _buttonActionGripperRelease));
1351
1371
1352
- // TODO(bzd) take channel nos from config, especially max
1353
- for (int ch = 8 ; ch <= 16 ;ch++) {
1354
- _assignableButtonActions.append (new AssignableButtonAction (this , QString (" Channel %1 direct PWM" ).arg (ch)));
1372
+ for (int ch = 8 ; ch <= MAX_RC_CHANNELS; ch++) {
1373
+ _assignableButtonActions.append (new AssignableButtonAction (this , QString (" Channel %1 direct PWM" ).arg (ch)));
1355
1374
}
1375
+ _clearRcOverrideButtonActions ();
1356
1376
1357
1377
_assignableButtonActions.append (new AssignableButtonAction (this , _buttonActionEmergencyStop));
1358
1378
for (auto & item : _customMavCommands) {
@@ -1369,8 +1389,27 @@ void Joystick::_buildActionList(Vehicle* activeVehicle)
1369
1389
bool Joystick::_executeRcOverrideButtonAction (int buttonIndex, bool buttonDown)
1370
1390
{
1371
1391
if (_buttonActionArray[buttonIndex]) {
1372
- _buttonActionArray[buttonIndex]->sendPwm (_activeVehicle, buttonDown);
1392
+ uint8_t channel = _buttonActionArray[buttonIndex]->rcChannel ();
1393
+ auto pwm = _buttonActionArray[buttonIndex]->calculatePwm (_activeVehicle, buttonDown);
1394
+ _rcOverride[channel-1 ] = pwm;
1395
+ _rcOverrideActive = true ;
1373
1396
return true ;
1374
1397
}
1375
1398
return false ;
1376
1399
}
1400
+
1401
+ void Joystick::_clearRcOverrideButtonActions () {
1402
+ qCDebug (JoystickLog) << " Clearing RC override button actions" ;
1403
+ for (int i = 0 ; i < MAX_RC_CHANNELS; i++) {
1404
+ _rcOverride[i] = -1 ;
1405
+ }
1406
+ }
1407
+
1408
+ uint16_t Joystick::_mapRcOverrideToRelease (uint8_t rcChannel, uint16_t value) {
1409
+ // UINT16_MAX - ignore
1410
+ // 0 Release
1411
+ if (value == 0 ) {
1412
+ return rcChannel < 9 ? 0 : UINT16_MAX - 1 ;
1413
+ }
1414
+ return value;
1415
+ }
0 commit comments