forked from mavlink/qgroundcontrol
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathJoystick.cc
786 lines (622 loc) · 25.7 KB
/
Joystick.cc
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#include "Joystick.h"
#include "QGC.h"
#include "AutoPilotPlugin.h"
#include "UAS.h"
#include <QSettings>
QGC_LOGGING_CATEGORY(JoystickLog, "JoystickLog")
QGC_LOGGING_CATEGORY(JoystickValuesLog, "JoystickValuesLog")
const char* Joystick::_settingsGroup = "Joysticks";
const char* Joystick::_calibratedSettingsKey = "Calibrated2"; // Increment number to force recalibration
const char* Joystick::_buttonActionSettingsKey = "ButtonActionName%1";
const char* Joystick::_throttleModeSettingsKey = "ThrottleMode";
const char* Joystick::_exponentialSettingsKey = "Exponential";
const char* Joystick::_accumulatorSettingsKey = "Accumulator";
const char* Joystick::_deadbandSettingsKey = "Deadband";
const char* Joystick::_txModeSettingsKey = NULL;
const char* Joystick::_fixedWingTXModeSettingsKey = "TXMode_FixedWing";
const char* Joystick::_multiRotorTXModeSettingsKey = "TXMode_MultiRotor";
const char* Joystick::_roverTXModeSettingsKey = "TXMode_Rover";
const char* Joystick::_vtolTXModeSettingsKey = "TXMode_VTOL";
const char* Joystick::_submarineTXModeSettingsKey = "TXMode_Submarine";
const char* Joystick::_rgFunctionSettingsKey[Joystick::maxFunction] = {
"RollAxis",
"PitchAxis",
"YawAxis",
"ThrottleAxis"
};
int Joystick::_transmitterMode = 2;
Joystick::Joystick(const QString& name, int axisCount, int buttonCount, int hatCount, MultiVehicleManager* multiVehicleManager)
: _exitThread(false)
, _name(name)
, _axisCount(axisCount)
, _buttonCount(buttonCount)
, _hatCount(hatCount)
, _hatButtonCount(4*hatCount)
, _totalButtonCount(_buttonCount+_hatButtonCount)
, _calibrationMode(CalibrationModeOff)
, _rgAxisValues(NULL)
, _rgCalibration(NULL)
, _rgButtonValues(NULL)
, _lastButtonBits(0)
, _throttleMode(ThrottleModeCenterZero)
, _exponential(0)
, _accumulator(false)
, _deadband(false)
, _activeVehicle(NULL)
, _pollingStartedForCalibration(false)
, _multiVehicleManager(multiVehicleManager)
{
_rgAxisValues = new int[_axisCount];
_rgCalibration = new Calibration_t[_axisCount];
_rgButtonValues = new bool[_totalButtonCount];
for (int i=0; i<_axisCount; i++) {
_rgAxisValues[i] = 0;
}
for (int i=0; i<_totalButtonCount; i++) {
_rgButtonValues[i] = false;
}
_loadSettings();
connect(_multiVehicleManager, &MultiVehicleManager::activeVehicleChanged, this, &Joystick::_activeVehicleChanged);
}
Joystick::~Joystick()
{
delete[] _rgAxisValues;
delete[] _rgCalibration;
delete[] _rgButtonValues;
}
void Joystick::_setDefaultCalibration(void) {
QSettings settings;
settings.beginGroup(_settingsGroup);
settings.beginGroup(_name);
_calibrated = settings.value(_calibratedSettingsKey, false).toBool();
// Only set default calibrations if we do not have a calibration for this gamecontroller
if(_calibrated) return;
for(int axis = 0; axis < _axisCount; axis++) {
Joystick::Calibration_t calibration;
_rgCalibration[axis] = calibration;
}
_rgCalibration[1].reversed = true;
_rgCalibration[3].reversed = true;
// Default TX Mode 2 axis assignments for gamecontrollers
_rgFunctionAxis[rollFunction] = 2;
_rgFunctionAxis[pitchFunction] = 3;
_rgFunctionAxis[yawFunction] = 0;
_rgFunctionAxis[throttleFunction] = 1;
_exponential = 0;
_accumulator = false;
_deadband = false;
_throttleMode = ThrottleModeCenterZero;
_calibrated = true;
_saveSettings();
}
void Joystick::_activeVehicleChanged(Vehicle *activeVehicle)
{
if(activeVehicle) {
if(activeVehicle->fixedWing()) {
_txModeSettingsKey = _fixedWingTXModeSettingsKey;
} else if(activeVehicle->multiRotor()) {
_txModeSettingsKey = _multiRotorTXModeSettingsKey;
} else if(activeVehicle->rover()) {
_txModeSettingsKey = _roverTXModeSettingsKey;
} else if(activeVehicle->vtol()) {
_txModeSettingsKey = _vtolTXModeSettingsKey;
} else if(activeVehicle->sub()) {
_txModeSettingsKey = _submarineTXModeSettingsKey;
} else {
_txModeSettingsKey = NULL;
qWarning() << "No valid joystick TXmode settings key for selected vehicle";
return;
}
QSettings settings;
settings.beginGroup(_settingsGroup);
int mode = settings.value(_txModeSettingsKey, activeVehicle->firmwarePlugin()->defaultJoystickTXMode()).toInt();
setTXMode(mode);
}
}
void Joystick::_loadSettings(void)
{
QSettings settings;
settings.beginGroup(_settingsGroup);
if(_txModeSettingsKey)
_transmitterMode = settings.value(_txModeSettingsKey, 2).toInt();
settings.beginGroup(_name);
bool badSettings = false;
bool convertOk;
qCDebug(JoystickLog) << "_loadSettings " << _name;
_calibrated = settings.value(_calibratedSettingsKey, false).toBool();
_exponential = settings.value(_exponentialSettingsKey, 0).toFloat();
_accumulator = settings.value(_accumulatorSettingsKey, false).toBool();
_deadband = settings.value(_deadbandSettingsKey, false).toBool();
_throttleMode = (ThrottleMode_t)settings.value(_throttleModeSettingsKey, ThrottleModeCenterZero).toInt(&convertOk);
badSettings |= !convertOk;
qCDebug(JoystickLog) << "_loadSettings calibrated:txmode:throttlemode:exponential:deadband:badsettings" << _calibrated << _transmitterMode << _throttleMode << _exponential << _deadband << badSettings;
QString minTpl ("Axis%1Min");
QString maxTpl ("Axis%1Max");
QString trimTpl ("Axis%1Trim");
QString revTpl ("Axis%1Rev");
QString deadbndTpl ("Axis%1Deadbnd");
for (int axis=0; axis<_axisCount; axis++) {
Calibration_t* calibration = &_rgCalibration[axis];
calibration->center = settings.value(trimTpl.arg(axis), 0).toInt(&convertOk);
badSettings |= !convertOk;
calibration->min = settings.value(minTpl.arg(axis), -32768).toInt(&convertOk);
badSettings |= !convertOk;
calibration->max = settings.value(maxTpl.arg(axis), 32767).toInt(&convertOk);
badSettings |= !convertOk;
calibration->deadband = settings.value(deadbndTpl.arg(axis), 0).toInt(&convertOk);
badSettings |= !convertOk;
calibration->reversed = settings.value(revTpl.arg(axis), false).toBool();
qCDebug(JoystickLog) << "_loadSettings axis:min:max:trim:reversed:deadband:badsettings" << axis << calibration->min << calibration->max << calibration->center << calibration->reversed << calibration->deadband << badSettings;
}
for (int function=0; function<maxFunction; function++) {
int functionAxis;
functionAxis = settings.value(_rgFunctionSettingsKey[function], -1).toInt(&convertOk);
badSettings |= !convertOk || (functionAxis == -1);
_rgFunctionAxis[function] = functionAxis;
qCDebug(JoystickLog) << "_loadSettings function:axis:badsettings" << function << functionAxis << badSettings;
}
// FunctionAxis mappings are always stored in TX mode 2
// Remap to stored TX mode in settings
_remapAxes(2, _transmitterMode, _rgFunctionAxis);
for (int button=0; button<_totalButtonCount; button++) {
_rgButtonActions << settings.value(QString(_buttonActionSettingsKey).arg(button), QString()).toString();
qCDebug(JoystickLog) << "_loadSettings button:action" << button << _rgButtonActions[button];
}
if (badSettings) {
_calibrated = false;
settings.setValue(_calibratedSettingsKey, false);
}
}
void Joystick::_saveSettings(void)
{
QSettings settings;
settings.beginGroup(_settingsGroup);
// Transmitter mode is static
// Save the mode we are using
if(_txModeSettingsKey)
settings.setValue(_txModeSettingsKey, _transmitterMode);
settings.beginGroup(_name);
settings.setValue(_calibratedSettingsKey, _calibrated);
settings.setValue(_exponentialSettingsKey, _exponential);
settings.setValue(_accumulatorSettingsKey, _accumulator);
settings.setValue(_deadbandSettingsKey, _deadband);
settings.setValue(_throttleModeSettingsKey, _throttleMode);
qCDebug(JoystickLog) << "_saveSettings calibrated:throttlemode:deadband:txmode" << _calibrated << _throttleMode << _deadband << _transmitterMode;
QString minTpl ("Axis%1Min");
QString maxTpl ("Axis%1Max");
QString trimTpl ("Axis%1Trim");
QString revTpl ("Axis%1Rev");
QString deadbndTpl ("Axis%1Deadbnd");
for (int axis=0; axis<_axisCount; axis++) {
Calibration_t* calibration = &_rgCalibration[axis];
settings.setValue(trimTpl.arg(axis), calibration->center);
settings.setValue(minTpl.arg(axis), calibration->min);
settings.setValue(maxTpl.arg(axis), calibration->max);
settings.setValue(revTpl.arg(axis), calibration->reversed);
settings.setValue(deadbndTpl.arg(axis), calibration->deadband);
qCDebug(JoystickLog) << "_saveSettings name:axis:min:max:trim:reversed:deadband"
<< _name
<< axis
<< calibration->min
<< calibration->max
<< calibration->center
<< calibration->reversed
<< calibration->deadband;
}
// Always save function Axis mappings in TX Mode 2
// Write mode 2 mappings without changing mapping currently in use
int temp[maxFunction];
_remapAxes(_transmitterMode, 2, temp);
for (int function=0; function<maxFunction; function++) {
settings.setValue(_rgFunctionSettingsKey[function], temp[function]);
qCDebug(JoystickLog) << "_saveSettings name:function:axis" << _name << function << _rgFunctionSettingsKey[function];
}
for (int button=0; button<_totalButtonCount; button++) {
settings.setValue(QString(_buttonActionSettingsKey).arg(button), _rgButtonActions[button]);
qCDebug(JoystickLog) << "_saveSettings button:action" << button << _rgButtonActions[button];
}
}
// Relative mappings of axis functions between different TX modes
int Joystick::_mapFunctionMode(int mode, int function) {
static const int mapping[][4] = {
{ 2, 1, 0, 3 },
{ 2, 3, 0, 1 },
{ 0, 1, 2, 3 },
{ 0, 3, 2, 1 }};
return mapping[mode-1][function];
}
// Remap current axis functions from current TX mode to new TX mode
void Joystick::_remapAxes(int currentMode, int newMode, int (&newMapping)[maxFunction]) {
int temp[maxFunction];
for(int function = 0; function < maxFunction; function++) {
temp[_mapFunctionMode(newMode, function)] = _rgFunctionAxis[_mapFunctionMode(currentMode, function)];
}
for(int function = 0; function < maxFunction; function++) {
newMapping[function] = temp[function];
}
}
void Joystick::setTXMode(int mode) {
if(mode > 0 && mode <= 4) {
_remapAxes(_transmitterMode, mode, _rgFunctionAxis);
_transmitterMode = mode;
_saveSettings();
} else {
qCWarning(JoystickLog) << "Invalid mode:" << mode;
}
}
/// Adjust the raw axis value to the -1:1 range given calibration information
float Joystick::_adjustRange(int value, Calibration_t calibration, bool withDeadbands)
{
float valueNormalized;
float axisLength;
float axisBasis;
if (value > calibration.center) {
axisBasis = 1.0f;
valueNormalized = value - calibration.center;
axisLength = calibration.max - calibration.center;
} else {
axisBasis = -1.0f;
valueNormalized = calibration.center - value;
axisLength = calibration.center - calibration.min;
}
float axisPercent;
if (withDeadbands) {
if (valueNormalized>calibration.deadband) {
axisPercent = (valueNormalized - calibration.deadband) / (axisLength - calibration.deadband);
} else if (valueNormalized<-calibration.deadband) {
axisPercent = (valueNormalized + calibration.deadband) / (axisLength - calibration.deadband);
} else {
axisPercent = 0.f;
}
}
else {
axisPercent = valueNormalized / axisLength;
}
float correctedValue = axisBasis * axisPercent;
if (calibration.reversed) {
correctedValue *= -1.0f;
}
#if 0
qCDebug(JoystickLog) << "_adjustRange corrected:value:min:max:center:reversed:deadband:basis:normalized:length"
<< correctedValue
<< value
<< calibration.min
<< calibration.max
<< calibration.center
<< calibration.reversed
<< calibration.deadband
<< axisBasis
<< valueNormalized
<< axisLength;
#endif
return std::max(-1.0f, std::min(correctedValue, 1.0f));
}
void Joystick::run(void)
{
_open();
while (!_exitThread) {
_update();
// Update axes
for (int axisIndex=0; axisIndex<_axisCount; axisIndex++) {
int newAxisValue = _getAxis(axisIndex);
// Calibration code requires signal to be emitted even if value hasn't changed
_rgAxisValues[axisIndex] = newAxisValue;
emit rawAxisValueChanged(axisIndex, newAxisValue);
}
// Update buttons
for (int buttonIndex=0; buttonIndex<_buttonCount; buttonIndex++) {
bool newButtonValue = _getButton(buttonIndex);
if (newButtonValue != _rgButtonValues[buttonIndex]) {
_rgButtonValues[buttonIndex] = newButtonValue;
emit rawButtonPressedChanged(buttonIndex, newButtonValue);
}
}
// Update hat - append hat buttons to the end of the normal button list
int numHatButtons = 4;
for (int hatIndex=0; hatIndex<_hatCount; hatIndex++) {
for (int hatButtonIndex=0; hatButtonIndex<numHatButtons; hatButtonIndex++) {
// Create new index value that includes the normal button list
int rgButtonValueIndex = hatIndex*numHatButtons + hatButtonIndex + _buttonCount;
// Get hat value from joystick
bool newButtonValue = _getHat(hatIndex,hatButtonIndex);
if (newButtonValue != _rgButtonValues[rgButtonValueIndex]) {
_rgButtonValues[rgButtonValueIndex] = newButtonValue;
emit rawButtonPressedChanged(rgButtonValueIndex, newButtonValue);
}
}
}
if (_calibrationMode != CalibrationModeCalibrating && _calibrated) {
int axis = _rgFunctionAxis[rollFunction];
float roll = _adjustRange(_rgAxisValues[axis], _rgCalibration[axis], _deadband);
axis = _rgFunctionAxis[pitchFunction];
float pitch = _adjustRange(_rgAxisValues[axis], _rgCalibration[axis], _deadband);
axis = _rgFunctionAxis[yawFunction];
float yaw = _adjustRange(_rgAxisValues[axis], _rgCalibration[axis],_deadband);
axis = _rgFunctionAxis[throttleFunction];
float throttle = _adjustRange(_rgAxisValues[axis], _rgCalibration[axis], _throttleMode==ThrottleModeDownZero?false:_deadband);
if ( _accumulator ) {
static float throttle_accu = 0.f;
throttle_accu += throttle*(40/1000.f); //for throttle to change from min to max it will take 1000ms (40ms is a loop time)
throttle_accu = std::max(static_cast<float>(-1.f), std::min(throttle_accu, static_cast<float>(1.f)));
throttle = throttle_accu;
}
float roll_limited = std::max(static_cast<float>(-M_PI_4), std::min(roll, static_cast<float>(M_PI_4)));
float pitch_limited = std::max(static_cast<float>(-M_PI_4), std::min(pitch, static_cast<float>(M_PI_4)));
float yaw_limited = std::max(static_cast<float>(-M_PI_4), std::min(yaw, static_cast<float>(M_PI_4)));
float throttle_limited = std::max(static_cast<float>(-M_PI_4), std::min(throttle, static_cast<float>(M_PI_4)));
// Map from unit circle to linear range and limit
roll = std::max(-1.0f, std::min(tanf(asinf(roll_limited)), 1.0f));
pitch = std::max(-1.0f, std::min(tanf(asinf(pitch_limited)), 1.0f));
yaw = std::max(-1.0f, std::min(tanf(asinf(yaw_limited)), 1.0f));
throttle = std::max(-1.0f, std::min(tanf(asinf(throttle_limited)), 1.0f));
if ( _exponential != 0 ) {
// Exponential (0% to -50% range like most RC radios)
//_exponential is set by a slider in joystickConfig.qml
// Calculate new RPY with exponential applied
roll = -_exponential*powf(roll,3) + (1+_exponential)*roll;
pitch = -_exponential*powf(pitch,3) + (1+_exponential)*pitch;
yaw = -_exponential*powf(yaw,3) + (1+_exponential)*yaw;
}
// Adjust throttle to 0:1 range
if (_throttleMode == ThrottleModeCenterZero && _activeVehicle->supportsThrottleModeCenterZero()) {
throttle = std::max(0.0f, throttle);
} else {
throttle = (throttle + 1.0f) / 2.0f;
}
// Set up button pressed information
// We only send the buttons the firmwware has reserved
int reservedButtonCount = _activeVehicle->manualControlReservedButtonCount();
if (reservedButtonCount == -1) {
reservedButtonCount = _totalButtonCount;
}
quint16 newButtonBits = 0; // New set of button which are down
quint16 buttonPressedBits = 0; // Buttons pressed for manualControl signal
for (int buttonIndex=0; buttonIndex<_totalButtonCount; buttonIndex++) {
quint16 buttonBit = 1 << buttonIndex;
if (!_rgButtonValues[buttonIndex]) {
// Button up, just record it
newButtonBits |= buttonBit;
} else {
if (_lastButtonBits & buttonBit) {
// Button was up last time through, but is now down which indicates a button press
qCDebug(JoystickLog) << "button triggered" << buttonIndex;
if (buttonIndex >= reservedButtonCount) {
// Button is above firmware reserved set
QString buttonAction =_rgButtonActions[buttonIndex];
if (!buttonAction.isEmpty()) {
_buttonAction(buttonAction);
}
}
}
// Mark the button as pressed as long as its pressed
buttonPressedBits |= buttonBit;
}
}
_lastButtonBits = newButtonBits;
qCDebug(JoystickValuesLog) << "name:roll:pitch:yaw:throttle" << name() << roll << -pitch << yaw << throttle;
emit manualControl(roll, -pitch, yaw, throttle, buttonPressedBits, _activeVehicle->joystickMode());
}
// Sleep, update rate of joystick is approx. 25 Hz (1000 ms / 25 = 40 ms)
QGC::SLEEP::msleep(40);
}
_close();
}
void Joystick::startPolling(Vehicle* vehicle)
{
if (vehicle) {
// If a vehicle is connected, disconnect it
if (_activeVehicle) {
UAS* uas = _activeVehicle->uas();
disconnect(this, &Joystick::manualControl, uas, &UAS::setExternalControlSetpoint);
}
// Always set up the new vehicle
_activeVehicle = vehicle;
// If joystick is not calibrated, disable it
if ( !_calibrated ) {
vehicle->setJoystickEnabled(false);
}
// Update qml in case of joystick transition
emit calibratedChanged(_calibrated);
// Only connect the new vehicle if it wants joystick data
if (vehicle->joystickEnabled()) {
_pollingStartedForCalibration = false;
UAS* uas = _activeVehicle->uas();
connect(this, &Joystick::manualControl, uas, &UAS::setExternalControlSetpoint);
// FIXME: ****
//connect(this, &Joystick::buttonActionTriggered, uas, &UAS::triggerAction);
}
}
if (!isRunning()) {
_exitThread = false;
start();
}
}
void Joystick::stopPolling(void)
{
if (isRunning()) {
if (_activeVehicle && _activeVehicle->joystickEnabled()) {
UAS* uas = _activeVehicle->uas();
// Neutral attitude controls
// emit manualControl(0, 0, 0, 0.5, 0, _activeVehicle->joystickMode());
disconnect(this, &Joystick::manualControl, uas, &UAS::setExternalControlSetpoint);
}
// FIXME: ****
//disconnect(this, &Joystick::buttonActionTriggered, uas, &UAS::triggerAction);
_exitThread = true;
}
}
void Joystick::setCalibration(int axis, Calibration_t& calibration)
{
if (!_validAxis(axis)) {
qCWarning(JoystickLog) << "Invalid axis index" << axis;
return;
}
_calibrated = true;
_rgCalibration[axis] = calibration;
_saveSettings();
emit calibratedChanged(_calibrated);
}
Joystick::Calibration_t Joystick::getCalibration(int axis)
{
if (!_validAxis(axis)) {
qCWarning(JoystickLog) << "Invalid axis index" << axis;
}
return _rgCalibration[axis];
}
void Joystick::setFunctionAxis(AxisFunction_t function, int axis)
{
if (!_validAxis(axis)) {
qCWarning(JoystickLog) << "Invalid axis index" << axis;
return;
}
_calibrated = true;
_rgFunctionAxis[function] = axis;
_saveSettings();
emit calibratedChanged(_calibrated);
}
int Joystick::getFunctionAxis(AxisFunction_t function)
{
if (function < 0 || function >= maxFunction) {
qCWarning(JoystickLog) << "Invalid function" << function;
}
return _rgFunctionAxis[function];
}
QStringList Joystick::actions(void)
{
QStringList list;
list << "Arm" << "Disarm";
if (_activeVehicle) {
list << _activeVehicle->flightModes();
}
return list;
}
void Joystick::setButtonAction(int button, const QString& action)
{
if (!_validButton(button)) {
qCWarning(JoystickLog) << "Invalid button index" << button;
return;
}
qDebug() << "setButtonAction" << action;
_rgButtonActions[button] = action;
_saveSettings();
emit buttonActionsChanged(buttonActions());
}
QString Joystick::getButtonAction(int button)
{
if (!_validButton(button)) {
qCWarning(JoystickLog) << "Invalid button index" << button;
}
return _rgButtonActions[button];
}
QVariantList Joystick::buttonActions(void)
{
QVariantList list;
for (int button=0; button<_totalButtonCount; button++) {
list += QVariant::fromValue(_rgButtonActions[button]);
}
return list;
}
int Joystick::throttleMode(void)
{
return _throttleMode;
}
void Joystick::setThrottleMode(int mode)
{
if (mode < 0 || mode >= ThrottleModeMax) {
qCWarning(JoystickLog) << "Invalid throttle mode" << mode;
return;
}
_throttleMode = (ThrottleMode_t)mode;
if (_throttleMode == ThrottleModeDownZero) {
setAccumulator(false);
}
_saveSettings();
emit throttleModeChanged(_throttleMode);
}
float Joystick::exponential(void)
{
return _exponential;
}
void Joystick::setExponential(float expo)
{
_exponential = expo;
_saveSettings();
emit exponentialChanged(_exponential);
}
bool Joystick::accumulator(void)
{
return _accumulator;
}
void Joystick::setAccumulator(bool accu)
{
_accumulator = accu;
_saveSettings();
emit accumulatorChanged(_accumulator);
}
bool Joystick::deadband(void)
{
return _deadband;
}
void Joystick::setDeadband(bool deadband)
{
_deadband = deadband;
_saveSettings();
}
void Joystick::startCalibrationMode(CalibrationMode_t mode)
{
if (mode == CalibrationModeOff) {
qWarning() << "Incorrect mode CalibrationModeOff";
return;
}
_calibrationMode = mode;
if (!isRunning()) {
_pollingStartedForCalibration = true;
startPolling(_multiVehicleManager->activeVehicle());
}
}
void Joystick::stopCalibrationMode(CalibrationMode_t mode)
{
if (mode == CalibrationModeOff) {
qWarning() << "Incorrect mode: CalibrationModeOff";
return;
}
if (mode == CalibrationModeCalibrating) {
_calibrationMode = CalibrationModeMonitor;
} else {
_calibrationMode = CalibrationModeOff;
if (_pollingStartedForCalibration) {
stopPolling();
}
}
}
void Joystick::_buttonAction(const QString& action)
{
if (!_activeVehicle || !_activeVehicle->joystickEnabled()) {
return;
}
if (action == "Arm") {
_activeVehicle->setArmed(true);
} else if (action == "Disarm") {
_activeVehicle->setArmed(false);
} else if (_activeVehicle->flightModes().contains(action)) {
_activeVehicle->setFlightMode(action);
} else {
qCDebug(JoystickLog) << "_buttonAction unknown action:" << action;
}
}
bool Joystick::_validAxis(int axis)
{
return axis >= 0 && axis < _axisCount;
}
bool Joystick::_validButton(int button)
{
return button >= 0 && button < _totalButtonCount;
}