forked from ArduPilot/ardupilot
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathjoystick.cpp
704 lines (653 loc) · 25.8 KB
/
joystick.cpp
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
#include "Sub.h"
// Functions that will handle joystick/gamepad input
// ----------------------------------------------------------------------------
// Anonymous namespace to hold variables used only in this file
namespace {
float cam_tilt = 1500.0;
int16_t lights1 = 1100;
int16_t lights2 = 1100;
int16_t rollTrim = 0;
int16_t pitchTrim = 0;
int16_t zTrim = 0;
int16_t xTrim = 0;
int16_t yTrim = 0;
int16_t video_switch = 1100;
int16_t x_last, y_last, z_last;
uint16_t buttons_prev;
// Servo control output channels
// TODO: Allow selecting output channels
const uint8_t SERVO_CHAN_1 = 9; // Pixhawk Aux1
const uint8_t SERVO_CHAN_2 = 10; // Pixhawk Aux2
const uint8_t SERVO_CHAN_3 = 11; // Pixhawk Aux3
uint8_t roll_pitch_flag = false; // Flag to adjust roll/pitch instead of forward/lateral
}
void Sub::init_joystick()
{
default_js_buttons();
lights1 = RC_Channels::rc_channel(8)->get_radio_min();
lights2 = RC_Channels::rc_channel(9)->get_radio_min();
set_mode(MANUAL, MODE_REASON_TX_COMMAND); // Initialize flight mode
if (g.numGainSettings < 1) {
g.numGainSettings.set_and_save(1);
}
if (g.numGainSettings == 1 || (g.gain_default < g.maxGain + 0.01 && g.gain_default > g.minGain - 0.01)) {
gain = constrain_float(g.gain_default, g.minGain, g.maxGain); // Use default gain parameter
} else {
// Use setting closest to average of minGain and maxGain
gain = g.minGain + (g.numGainSettings/2 - 1) * (g.maxGain - g.minGain) / (g.numGainSettings - 1);
}
gain = constrain_float(gain, 0.1, 1.0);
}
void Sub::transform_manual_control_to_rc_override(int16_t x, int16_t y, int16_t z, int16_t r, uint16_t buttons)
{
int16_t channels[11];
float rpyScale = 0.4*gain; // Scale -1000-1000 to -400-400 with gain
float throttleScale = 0.8*gain*g.throttle_gain; // Scale 0-1000 to 0-800 times gain
int16_t rpyCenter = 1500;
int16_t throttleBase = 1500-500*throttleScale;
bool shift = false;
// Neutralize camera tilt speed setpoint
cam_tilt = 1500;
// Detect if any shift button is pressed
for (uint8_t i = 0 ; i < 16 ; i++) {
if ((buttons & (1 << i)) && get_button(i)->function() == JSButton::button_function_t::k_shift) {
shift = true;
}
}
// Act if button is pressed
// Only act upon pressing button and ignore holding. This provides compatibility with Taranis as joystick.
for (uint8_t i = 0 ; i < 16 ; i++) {
if ((buttons & (1 << i))) {
handle_jsbutton_press(i,shift,(buttons_prev & (1 << i)));
// buttonDebounce = tnow_ms;
} else if (buttons_prev & (1 << i)) {
handle_jsbutton_release(i, shift);
}
}
buttons_prev = buttons;
// attitude mode:
if (roll_pitch_flag == 1) {
// adjust roll/pitch trim with joystick input instead of forward/lateral
pitchTrim = -x * rpyScale;
rollTrim = y * rpyScale;
}
channels[0] = constrain_int16(pitchTrim + rpyCenter,1100,1900); // pitch
channels[1] = constrain_int16(rollTrim + rpyCenter,1100,1900); // roll
channels[2] = constrain_int16((z+zTrim)*throttleScale+throttleBase,1100,1900); // throttle
channels[3] = constrain_int16(r*rpyScale+rpyCenter,1100,1900); // yaw
// maneuver mode:
if (roll_pitch_flag == 0) {
// adjust forward and lateral with joystick input instead of roll and pitch
channels[4] = constrain_int16((x+xTrim)*rpyScale+rpyCenter,1100,1900); // forward for ROV
channels[5] = constrain_int16((y+yTrim)*rpyScale+rpyCenter,1100,1900); // lateral for ROV
} else {
// neutralize forward and lateral input while we are adjusting roll and pitch
channels[4] = constrain_int16(xTrim*rpyScale+rpyCenter,1100,1900); // forward for ROV
channels[5] = constrain_int16(yTrim*rpyScale+rpyCenter,1100,1900); // lateral for ROV
}
channels[6] = 0; // Unused
channels[7] = cam_tilt; // camera tilt
channels[8] = lights1; // lights 1
channels[9] = lights2; // lights 2
channels[10] = video_switch; // video switch
// Store old x, y, z values for use in input hold logic
x_last = x;
y_last = y;
z_last = z;
hal.rcin->set_overrides(channels, 10);
}
void Sub::handle_jsbutton_press(uint8_t button, bool shift, bool held)
{
// Act based on the function assigned to this button
switch (get_button(button)->function(shift)) {
case JSButton::button_function_t::k_arm_toggle:
if (motors.armed()) {
init_disarm_motors();
} else {
init_arm_motors(true);
}
break;
case JSButton::button_function_t::k_arm:
init_arm_motors(true);
break;
case JSButton::button_function_t::k_disarm:
init_disarm_motors();
break;
case JSButton::button_function_t::k_mode_manual:
set_mode(MANUAL, MODE_REASON_TX_COMMAND);
break;
case JSButton::button_function_t::k_mode_stabilize:
set_mode(STABILIZE, MODE_REASON_TX_COMMAND);
break;
case JSButton::button_function_t::k_mode_depth_hold:
set_mode(ALT_HOLD, MODE_REASON_TX_COMMAND);
break;
case JSButton::button_function_t::k_mode_auto:
set_mode(AUTO, MODE_REASON_TX_COMMAND);
break;
case JSButton::button_function_t::k_mode_guided:
set_mode(GUIDED, MODE_REASON_TX_COMMAND);
break;
case JSButton::button_function_t::k_mode_circle:
set_mode(CIRCLE, MODE_REASON_TX_COMMAND);
break;
case JSButton::button_function_t::k_mode_acro:
set_mode(ACRO, MODE_REASON_TX_COMMAND);
break;
case JSButton::button_function_t::k_mode_poshold:
set_mode(POSHOLD, MODE_REASON_TX_COMMAND);
break;
case JSButton::button_function_t::k_mount_center:
camera_mount.set_angle_targets(0, 0, 0);
// for some reason the call to set_angle_targets changes the mode to mavlink targeting!
camera_mount.set_mode(MAV_MOUNT_MODE_RC_TARGETING);
break;
case JSButton::button_function_t::k_mount_tilt_up:
cam_tilt = 1900;
break;
case JSButton::button_function_t::k_mount_tilt_down:
cam_tilt = 1100;
break;
case JSButton::button_function_t::k_camera_trigger:
break;
case JSButton::button_function_t::k_camera_source_toggle:
if (!held) {
static bool video_toggle = false;
video_toggle = !video_toggle;
if (video_toggle) {
video_switch = 1900;
gcs().send_text(MAV_SEVERITY_INFO,"Video Toggle: Source 2");
} else {
video_switch = 1100;
gcs().send_text(MAV_SEVERITY_INFO,"Video Toggle: Source 1");
}
}
break;
case JSButton::button_function_t::k_mount_pan_right:
// Not implemented
break;
case JSButton::button_function_t::k_mount_pan_left:
// Not implemented
break;
case JSButton::button_function_t::k_lights1_cycle:
if (!held) {
static bool increasing = true;
RC_Channel* chan = RC_Channels::rc_channel(8);
uint16_t min = chan->get_radio_min();
uint16_t max = chan->get_radio_max();
uint16_t step = (max - min) / g.lights_steps;
if (increasing) {
lights1 = constrain_float(lights1 + step, min, max);
} else {
lights1 = constrain_float(lights1 - step, min, max);
}
if (lights1 >= max || lights1 <= min) {
increasing = !increasing;
}
}
break;
case JSButton::button_function_t::k_lights1_brighter:
if (!held) {
RC_Channel* chan = RC_Channels::rc_channel(8);
uint16_t min = chan->get_radio_min();
uint16_t max = chan->get_radio_max();
uint16_t step = (max - min) / g.lights_steps;
lights1 = constrain_float(lights1 + step, min, max);
}
break;
case JSButton::button_function_t::k_lights1_dimmer:
if (!held) {
RC_Channel* chan = RC_Channels::rc_channel(8);
uint16_t min = chan->get_radio_min();
uint16_t max = chan->get_radio_max();
uint16_t step = (max - min) / g.lights_steps;
lights1 = constrain_float(lights1 - step, min, max);
}
break;
case JSButton::button_function_t::k_lights2_cycle:
if (!held) {
static bool increasing = true;
RC_Channel* chan = RC_Channels::rc_channel(9);
uint16_t min = chan->get_radio_min();
uint16_t max = chan->get_radio_max();
uint16_t step = (max - min) / g.lights_steps;
if (increasing) {
lights2 = constrain_float(lights2 + step, min, max);
} else {
lights2 = constrain_float(lights2 - step, min, max);
}
if (lights2 >= max || lights2 <= min) {
increasing = !increasing;
}
}
break;
case JSButton::button_function_t::k_lights2_brighter:
if (!held) {
RC_Channel* chan = RC_Channels::rc_channel(9);
uint16_t min = chan->get_radio_min();
uint16_t max = chan->get_radio_max();
uint16_t step = (max - min) / g.lights_steps;
lights2 = constrain_float(lights2 + step, min, max);
}
break;
case JSButton::button_function_t::k_lights2_dimmer:
if (!held) {
RC_Channel* chan = RC_Channels::rc_channel(9);
uint16_t min = chan->get_radio_min();
uint16_t max = chan->get_radio_max();
uint16_t step = (max - min) / g.lights_steps;
lights2 = constrain_float(lights2 - step, min, max);
}
break;
case JSButton::button_function_t::k_gain_toggle:
if (!held) {
static bool lowGain = false;
lowGain = !lowGain;
if (lowGain) {
gain = 0.5f;
} else {
gain = 1.0f;
}
gcs().send_text(MAV_SEVERITY_INFO,"#Gain: %2.0f%%",(double)gain*100);
}
break;
case JSButton::button_function_t::k_gain_inc:
if (!held) {
// check that our gain parameters are in correct range, update in eeprom and notify gcs if needed
g.minGain.set_and_save(constrain_float(g.minGain, 0.10, 0.80));
g.maxGain.set_and_save(constrain_float(g.maxGain, g.minGain, 1.0));
g.numGainSettings.set_and_save(constrain_int16(g.numGainSettings, 1, 10));
if (g.numGainSettings == 1) {
gain = constrain_float(g.gain_default, g.minGain, g.maxGain);
} else {
gain = constrain_float(gain + (g.maxGain-g.minGain)/(g.numGainSettings-1), g.minGain, g.maxGain);
}
gcs().send_text(MAV_SEVERITY_INFO,"#Gain is %2.0f%%",(double)gain*100);
}
break;
case JSButton::button_function_t::k_gain_dec:
if (!held) {
// check that our gain parameters are in correct range, update in eeprom and notify gcs if needed
g.minGain.set_and_save(constrain_float(g.minGain, 0.10, 0.80));
g.maxGain.set_and_save(constrain_float(g.maxGain, g.minGain, 1.0));
g.numGainSettings.set_and_save(constrain_int16(g.numGainSettings, 1, 10));
if (g.numGainSettings == 1) {
gain = constrain_float(g.gain_default, g.minGain, g.maxGain);
} else {
gain = constrain_float(gain - (g.maxGain-g.minGain)/(g.numGainSettings-1), g.minGain, g.maxGain);
}
gcs().send_text(MAV_SEVERITY_INFO,"#Gain is %2.0f%%",(double)gain*100);
}
break;
case JSButton::button_function_t::k_trim_roll_inc:
rollTrim = constrain_float(rollTrim+10,-200,200);
break;
case JSButton::button_function_t::k_trim_roll_dec:
rollTrim = constrain_float(rollTrim-10,-200,200);
break;
case JSButton::button_function_t::k_trim_pitch_inc:
pitchTrim = constrain_float(pitchTrim+10,-200,200);
break;
case JSButton::button_function_t::k_trim_pitch_dec:
pitchTrim = constrain_float(pitchTrim-10,-200,200);
break;
case JSButton::button_function_t::k_input_hold_set:
if(!motors.armed()) {
break;
}
if (!held) {
zTrim = abs(z_last-500) > 50 ? z_last-500 : 0;
xTrim = abs(x_last) > 50 ? x_last : 0;
yTrim = abs(y_last) > 50 ? y_last : 0;
bool input_hold_engaged_last = input_hold_engaged;
input_hold_engaged = zTrim || xTrim || yTrim;
if (input_hold_engaged) {
gcs().send_text(MAV_SEVERITY_INFO,"#Input Hold Set");
} else if (input_hold_engaged_last) {
gcs().send_text(MAV_SEVERITY_INFO,"#Input Hold Disabled");
}
}
break;
case JSButton::button_function_t::k_relay_1_on:
relay.on(0);
break;
case JSButton::button_function_t::k_relay_1_off:
relay.off(0);
break;
case JSButton::button_function_t::k_relay_1_toggle:
if (!held) {
relay.toggle(0);
}
break;
case JSButton::button_function_t::k_relay_1_momentary:
if (!held) {
relay.on(0);
}
break;
case JSButton::button_function_t::k_relay_2_on:
relay.on(1);
break;
case JSButton::button_function_t::k_relay_2_off:
relay.off(1);
break;
case JSButton::button_function_t::k_relay_2_toggle:
if (!held) {
relay.toggle(1);
}
break;
case JSButton::button_function_t::k_relay_2_momentary:
if (!held) {
relay.on(1);
}
break;
case JSButton::button_function_t::k_relay_3_on:
relay.on(2);
break;
case JSButton::button_function_t::k_relay_3_off:
relay.off(2);
break;
case JSButton::button_function_t::k_relay_3_toggle:
if (!held) {
relay.toggle(2);
}
break;
case JSButton::button_function_t::k_relay_3_momentary:
if (!held) {
relay.on(2);
}
break;
case JSButton::button_function_t::k_relay_4_on:
relay.on(3);
break;
case JSButton::button_function_t::k_relay_4_off:
relay.off(3);
break;
case JSButton::button_function_t::k_relay_4_toggle:
if (!held) {
relay.toggle(3);
}
break;
case JSButton::button_function_t::k_relay_4_momentary:
if (!held) {
relay.on(3);
}
break;
////////////////////////////////////////////////
// Servo functions
// TODO: initialize
case JSButton::button_function_t::k_servo_1_inc:
{
SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_1 - 1); // 0-indexed
uint16_t pwm_out = hal.rcout->read(SERVO_CHAN_1 - 1); // 0-indexed
pwm_out = constrain_int16(pwm_out + 50, chan->get_output_min(), chan->get_output_max());
ServoRelayEvents.do_set_servo(SERVO_CHAN_1, pwm_out); // 1-indexed
}
break;
case JSButton::button_function_t::k_servo_1_dec:
{
SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_1 - 1); // 0-indexed
uint16_t pwm_out = hal.rcout->read(SERVO_CHAN_1 - 1); // 0-indexed
pwm_out = constrain_int16(pwm_out - 50, chan->get_output_min(), chan->get_output_max());
ServoRelayEvents.do_set_servo(SERVO_CHAN_1, pwm_out); // 1-indexed
}
break;
case JSButton::button_function_t::k_servo_1_min:
case JSButton::button_function_t::k_servo_1_min_momentary:
{
SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_1 - 1); // 0-indexed
ServoRelayEvents.do_set_servo(SERVO_CHAN_1, chan->get_output_min()); // 1-indexed
}
break;
case JSButton::button_function_t::k_servo_1_min_toggle:
if(!held) {
SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_1 - 1); // 0-indexed
if(chan->get_output_pwm() != chan->get_output_min()) {
ServoRelayEvents.do_set_servo(SERVO_CHAN_1, chan->get_output_min()); // 1-indexed
} else {
ServoRelayEvents.do_set_servo(SERVO_CHAN_1, chan->get_trim()); // 1-indexed
}
}
break;
case JSButton::button_function_t::k_servo_1_max:
case JSButton::button_function_t::k_servo_1_max_momentary:
{
SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_1 - 1); // 0-indexed
ServoRelayEvents.do_set_servo(SERVO_CHAN_1, chan->get_output_max()); // 1-indexed
}
break;
case JSButton::button_function_t::k_servo_1_max_toggle:
if(!held) {
SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_1 - 1); // 0-indexed
if(chan->get_output_pwm() != chan->get_output_max()) {
ServoRelayEvents.do_set_servo(SERVO_CHAN_1, chan->get_output_max()); // 1-indexed
} else {
ServoRelayEvents.do_set_servo(SERVO_CHAN_1, chan->get_trim()); // 1-indexed
}
}
break;
case JSButton::button_function_t::k_servo_1_center:
{
SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_1 - 1); // 0-indexed
ServoRelayEvents.do_set_servo(SERVO_CHAN_1, chan->get_trim()); // 1-indexed
}
break;
case JSButton::button_function_t::k_servo_2_inc:
{
SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_2 - 1); // 0-indexed
uint16_t pwm_out = hal.rcout->read(SERVO_CHAN_2 - 1); // 0-indexed
pwm_out = constrain_int16(pwm_out + 50, chan->get_output_min(), chan->get_output_max());
ServoRelayEvents.do_set_servo(SERVO_CHAN_2, pwm_out); // 1-indexed
}
break;
case JSButton::button_function_t::k_servo_2_dec:
{
SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_2 - 1); // 0-indexed
uint16_t pwm_out = hal.rcout->read(SERVO_CHAN_2 - 1); // 0-indexed
pwm_out = constrain_int16(pwm_out - 50, chan->get_output_min(), chan->get_output_max());
ServoRelayEvents.do_set_servo(SERVO_CHAN_2, pwm_out); // 1-indexed
}
break;
case JSButton::button_function_t::k_servo_2_min:
case JSButton::button_function_t::k_servo_2_min_momentary:
{
SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_2 - 1); // 0-indexed
ServoRelayEvents.do_set_servo(SERVO_CHAN_2, chan->get_output_min()); // 1-indexed
}
break;
case JSButton::button_function_t::k_servo_2_max:
case JSButton::button_function_t::k_servo_2_max_momentary:
{
SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_2 - 1); // 0-indexed
ServoRelayEvents.do_set_servo(SERVO_CHAN_2, chan->get_output_max()); // 1-indexed
}
break;
case JSButton::button_function_t::k_servo_2_center:
{
SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_2 - 1); // 0-indexed
ServoRelayEvents.do_set_servo(SERVO_CHAN_2, chan->get_trim()); // 1-indexed
}
break;
case JSButton::button_function_t::k_servo_3_inc:
{
SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_3 - 1); // 0-indexed
uint16_t pwm_out = hal.rcout->read(SERVO_CHAN_3 - 1); // 0-indexed
pwm_out = constrain_int16(pwm_out + 50, chan->get_output_min(), chan->get_output_max());
ServoRelayEvents.do_set_servo(SERVO_CHAN_3, pwm_out); // 1-indexed
}
break;
case JSButton::button_function_t::k_servo_3_dec:
{
SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_3 - 1); // 0-indexed
uint16_t pwm_out = hal.rcout->read(SERVO_CHAN_3 - 1); // 0-indexed
pwm_out = constrain_int16(pwm_out - 50, chan->get_output_min(), chan->get_output_max());
ServoRelayEvents.do_set_servo(SERVO_CHAN_3, pwm_out); // 1-indexed
}
break;
case JSButton::button_function_t::k_servo_3_min:
case JSButton::button_function_t::k_servo_3_min_momentary:
{
SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_3 - 1); // 0-indexed
ServoRelayEvents.do_set_servo(SERVO_CHAN_3, chan->get_output_min()); // 1-indexed
}
break;
case JSButton::button_function_t::k_servo_3_max:
case JSButton::button_function_t::k_servo_3_max_momentary:
{
SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_3 - 1); // 0-indexed
ServoRelayEvents.do_set_servo(SERVO_CHAN_3, chan->get_output_max()); // 1-indexed
}
break;
case JSButton::button_function_t::k_servo_3_center:
{
SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_3 - 1); // 0-indexed
ServoRelayEvents.do_set_servo(SERVO_CHAN_3, chan->get_trim()); // 1-indexed
}
break;
case JSButton::button_function_t::k_roll_pitch_toggle:
if (!held) {
roll_pitch_flag = !roll_pitch_flag;
}
break;
case JSButton::button_function_t::k_custom_1:
// Not implemented
break;
case JSButton::button_function_t::k_custom_2:
// Not implemented
break;
case JSButton::button_function_t::k_custom_3:
// Not implemented
break;
case JSButton::button_function_t::k_custom_4:
// Not implemented
break;
case JSButton::button_function_t::k_custom_5:
// Not implemented
break;
case JSButton::button_function_t::k_custom_6:
// Not implemented
break;
}
}
void Sub::handle_jsbutton_release(uint8_t button, bool shift) {
// Act based on the function assigned to this button
switch (get_button(button)->function(shift)) {
case JSButton::button_function_t::k_relay_1_momentary:
relay.off(0);
break;
case JSButton::button_function_t::k_relay_2_momentary:
relay.off(1);
break;
case JSButton::button_function_t::k_relay_3_momentary:
relay.off(2);
break;
case JSButton::button_function_t::k_relay_4_momentary:
relay.off(3);
break;
case JSButton::button_function_t::k_servo_1_min_momentary:
case JSButton::button_function_t::k_servo_1_max_momentary:
{
SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_1 - 1); // 0-indexed
ServoRelayEvents.do_set_servo(SERVO_CHAN_1, chan->get_trim()); // 1-indexed
}
break;
case JSButton::button_function_t::k_servo_2_min_momentary:
case JSButton::button_function_t::k_servo_2_max_momentary:
{
SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_2 - 1); // 0-indexed
ServoRelayEvents.do_set_servo(SERVO_CHAN_2, chan->get_trim()); // 1-indexed
}
break;
case JSButton::button_function_t::k_servo_3_min_momentary:
case JSButton::button_function_t::k_servo_3_max_momentary:
{
SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_3 - 1); // 0-indexed
ServoRelayEvents.do_set_servo(SERVO_CHAN_3, chan->get_trim()); // 1-indexed
}
break;
}
}
JSButton* Sub::get_button(uint8_t index)
{
// Help to access appropriate parameter
switch (index) {
case 0:
return &g.jbtn_0;
case 1:
return &g.jbtn_1;
case 2:
return &g.jbtn_2;
case 3:
return &g.jbtn_3;
case 4:
return &g.jbtn_4;
case 5:
return &g.jbtn_5;
case 6:
return &g.jbtn_6;
case 7:
return &g.jbtn_7;
case 8:
return &g.jbtn_8;
case 9:
return &g.jbtn_9;
case 10:
return &g.jbtn_10;
case 11:
return &g.jbtn_11;
case 12:
return &g.jbtn_12;
case 13:
return &g.jbtn_13;
case 14:
return &g.jbtn_14;
case 15:
return &g.jbtn_15;
default:
return &g.jbtn_0;
}
}
void Sub::default_js_buttons()
{
JSButton::button_function_t defaults[16][2] = {
{JSButton::button_function_t::k_none, JSButton::button_function_t::k_none},
{JSButton::button_function_t::k_mode_manual, JSButton::button_function_t::k_none},
{JSButton::button_function_t::k_mode_depth_hold, JSButton::button_function_t::k_none},
{JSButton::button_function_t::k_mode_stabilize, JSButton::button_function_t::k_none},
{JSButton::button_function_t::k_disarm, JSButton::button_function_t::k_none},
{JSButton::button_function_t::k_shift, JSButton::button_function_t::k_none},
{JSButton::button_function_t::k_arm, JSButton::button_function_t::k_none},
{JSButton::button_function_t::k_mount_center, JSButton::button_function_t::k_none},
{JSButton::button_function_t::k_input_hold_set, JSButton::button_function_t::k_none},
{JSButton::button_function_t::k_mount_tilt_down, JSButton::button_function_t::k_none},
{JSButton::button_function_t::k_mount_tilt_up, JSButton::button_function_t::k_none},
{JSButton::button_function_t::k_gain_inc, JSButton::button_function_t::k_trim_pitch_dec},
{JSButton::button_function_t::k_gain_dec, JSButton::button_function_t::k_trim_pitch_inc},
{JSButton::button_function_t::k_lights1_dimmer, JSButton::button_function_t::k_trim_roll_dec},
{JSButton::button_function_t::k_lights1_brighter, JSButton::button_function_t::k_trim_roll_inc},
{JSButton::button_function_t::k_none, JSButton::button_function_t::k_none},
};
for (int i = 0; i < 16; i++) {
get_button(i)->set_default(defaults[i][0], defaults[i][1]);
}
}
void Sub::set_neutral_controls()
{
int16_t channels[11];
for (uint8_t i = 0; i < 6; i++) {
channels[i] = 1500;
}
for (uint8_t i = 6; i < 11; i++) {
channels[i] = 0xffff;
}
hal.rcin->set_overrides(channels, 10);
// Clear pitch/roll trim settings
pitchTrim = 0;
rollTrim = 0;
}
void Sub::clear_input_hold()
{
xTrim = 0;
yTrim = 0;
zTrim = 0;
input_hold_engaged = false;
}