Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduSub/joystick.cpp
9320 views
1
#include "Sub.h"
2
#include "mode.h"
3
4
// Functions that will handle joystick/gamepad input
5
// ----------------------------------------------------------------------------
6
7
// Anonymous namespace to hold variables used only in this file
8
namespace {
9
#if HAL_MOUNT_ENABLED
10
float cam_tilt = 1500.0;
11
float cam_pan = 1500.0;
12
#endif // HAL_MOUNT_ENABLED
13
float lights1 = 0;
14
float lights2 = 0;
15
int16_t rollTrim = 0;
16
int16_t pitchTrim = 0;
17
int16_t zTrim = 0;
18
int16_t xTrim = 0;
19
int16_t yTrim = 0;
20
int16_t x_last, y_last, z_last;
21
uint32_t buttons_prev;
22
23
bool controls_reset_since_input_hold = true;
24
}
25
26
void Sub::init_joystick()
27
{
28
default_js_buttons();
29
30
set_mode(Mode::Number::MANUAL, ModeReason::RC_COMMAND); // Initialize flight mode
31
32
if (g.numGainSettings < 1) {
33
g.numGainSettings.set_and_save(1);
34
}
35
36
if (g.numGainSettings == 1 || (g.gain_default < g.maxGain + 0.01 && g.gain_default > g.minGain - 0.01)) {
37
gain = constrain_float(g.gain_default, g.minGain, g.maxGain); // Use default gain parameter
38
} else {
39
// Use setting closest to average of minGain and maxGain
40
gain = g.minGain + (g.numGainSettings/2 - 1) * (g.maxGain - g.minGain) / (g.numGainSettings - 1);
41
}
42
43
gain = constrain_float(gain, 0.1, 1.0);
44
SRV_Channels::set_output_scaled(SRV_Channel::k_lights1, 0.0);
45
SRV_Channels::set_output_scaled(SRV_Channel::k_lights2, 0.0);
46
SRV_Channels::set_output_scaled(SRV_Channel::k_video_switch, 0.0);
47
}
48
49
void Sub::transform_manual_control_to_rc_override(int16_t x, int16_t y, int16_t z, int16_t r, uint16_t buttons, uint16_t buttons2, uint8_t enabled_extensions,
50
int16_t s,
51
int16_t t,
52
int16_t aux1,
53
int16_t aux2,
54
int16_t aux3,
55
int16_t aux4,
56
int16_t aux5,
57
int16_t aux6)
58
{
59
60
float rpyScale = 0.4*gain; // Scale -1000-1000 to -400-400 with gain
61
float throttleScale = 0.8*gain*g.throttle_gain; // Scale 0-1000 to 0-800 times gain
62
int16_t rpyCenter = 1500;
63
int16_t throttleBase = 1500-500*throttleScale;
64
65
bool shift = false;
66
67
#if HAL_MOUNT_ENABLED
68
// Neutralize camera tilt and pan speed setpoint
69
cam_tilt = 1500;
70
cam_pan = 1500;
71
#endif // HAL_MOUNT_ENABLED
72
73
uint32_t all_buttons = buttons | (buttons2 << 16);
74
// Detect if any shift button is pressed
75
for (uint8_t i = 0 ; i < 32 ; i++) {
76
if ((all_buttons & (1 << i)) && get_button(i)->function() == JSButton::button_function_t::k_shift) {
77
shift = true;
78
}
79
}
80
81
// Act if button is pressed
82
// Only act upon pressing button and ignore holding. This provides compatibility with Taranis as joystick.
83
for (uint8_t i = 0 ; i < 32 ; i++) {
84
if ((all_buttons & (1 << i))) {
85
handle_jsbutton_press(i,shift,(buttons_prev & (1 << i)));
86
// buttonDebounce = tnow_ms;
87
} else if (buttons_prev & (1 << i)) {
88
handle_jsbutton_release(i, shift);
89
}
90
}
91
92
buttons_prev = all_buttons;
93
94
// attitude mode:
95
if (roll_pitch_flag == 1) {
96
// adjust roll/pitch trim with joystick input instead of forward/lateral
97
pitchTrim = -x * rpyScale;
98
rollTrim = y * rpyScale;
99
}
100
101
uint32_t tnow = AP_HAL::millis();
102
103
int16_t zTot;
104
int16_t yTot;
105
int16_t xTot;
106
107
if (!controls_reset_since_input_hold) {
108
zTot = zTrim + 500; // 500 is neutral for throttle
109
yTot = yTrim;
110
xTot = xTrim;
111
// if all 3 axes return to neutral, than we're ready to accept input again
112
controls_reset_since_input_hold = (abs(z - 500) < 50) && (abs(y) < 50) && (abs(x) < 50);
113
} else {
114
zTot = z + zTrim;
115
yTot = y + yTrim;
116
xTot = x + xTrim;
117
}
118
119
channel_pitch->set_override(constrain_int16(s + pitchTrim + rpyCenter,1100,1900), tnow);
120
channel_roll->set_override(constrain_int16(t + rollTrim + rpyCenter,1100,1900), tnow);
121
122
channel_throttle->set_override(constrain_int16((zTot)*throttleScale+throttleBase,1100,1900), tnow);
123
channel_yaw->set_override(constrain_int16(r*rpyScale+rpyCenter,1100,1900), tnow);
124
125
// maneuver mode:
126
if (roll_pitch_flag == 0) {
127
// adjust forward and lateral with joystick input instead of roll and pitch
128
channel_forward->set_override(constrain_int16((xTot)*rpyScale+rpyCenter,1100,1900), tnow);
129
channel_lateral->set_override(constrain_int16((yTot)*rpyScale+rpyCenter,1100,1900), tnow);
130
} else {
131
// neutralize forward and lateral input while we are adjusting roll and pitch
132
channel_forward->set_override(constrain_int16(xTrim*rpyScale+rpyCenter,1100,1900), tnow);
133
channel_lateral->set_override(constrain_int16(yTrim*rpyScale+rpyCenter,1100,1900), tnow);
134
}
135
136
#if HAL_MOUNT_ENABLED
137
RC_Channel *cam_pan_chan = rc().find_channel_for_option(RC_Channel::AUX_FUNC::MOUNT1_YAW);
138
if (cam_pan_chan != nullptr) {
139
cam_pan_chan->set_override(cam_pan, tnow);
140
}
141
RC_Channel *cam_tilt_chan = rc().find_channel_for_option(RC_Channel::AUX_FUNC::MOUNT1_PITCH);
142
if (cam_tilt_chan != nullptr) {
143
cam_tilt_chan->set_override(cam_tilt, tnow);
144
}
145
#endif // HAL_MOUNT_ENABLED
146
147
// Store old x, y, z values for use in input hold logic
148
x_last = x;
149
y_last = y;
150
z_last = z;
151
}
152
153
void Sub::handle_jsbutton_press(uint8_t _button, bool shift, bool held)
154
{
155
// Act based on the function assigned to this button
156
switch (get_button(_button)->function(shift)) {
157
case JSButton::button_function_t::k_arm_toggle:
158
if (motors.armed()) {
159
arming.disarm(AP_Arming::Method::MAVLINK);
160
} else {
161
arming.arm(AP_Arming::Method::MAVLINK);
162
}
163
break;
164
case JSButton::button_function_t::k_arm:
165
arming.arm(AP_Arming::Method::MAVLINK);
166
break;
167
case JSButton::button_function_t::k_disarm:
168
arming.disarm(AP_Arming::Method::MAVLINK);
169
break;
170
171
case JSButton::button_function_t::k_mode_manual:
172
set_mode(Mode::Number::MANUAL, ModeReason::RC_COMMAND);
173
break;
174
case JSButton::button_function_t::k_mode_stabilize:
175
set_mode(Mode::Number::STABILIZE, ModeReason::RC_COMMAND);
176
break;
177
case JSButton::button_function_t::k_mode_depth_hold:
178
set_mode(Mode::Number::ALT_HOLD, ModeReason::RC_COMMAND);
179
break;
180
case JSButton::button_function_t::k_mode_auto:
181
set_mode(Mode::Number::AUTO, ModeReason::RC_COMMAND);
182
break;
183
case JSButton::button_function_t::k_mode_guided:
184
set_mode(Mode::Number::GUIDED, ModeReason::RC_COMMAND);
185
break;
186
case JSButton::button_function_t::k_mode_circle:
187
set_mode(Mode::Number::CIRCLE, ModeReason::RC_COMMAND);
188
break;
189
case JSButton::button_function_t::k_mode_acro:
190
set_mode(Mode::Number::ACRO, ModeReason::RC_COMMAND);
191
break;
192
case JSButton::button_function_t::k_mode_poshold:
193
set_mode(Mode::Number::POSHOLD, ModeReason::RC_COMMAND);
194
break;
195
#if AP_RANGEFINDER_ENABLED
196
case JSButton::button_function_t::k_mode_surftrak:
197
set_mode(Mode::Number::SURFTRAK, ModeReason::RC_COMMAND);
198
break;
199
#endif
200
#if HAL_MOUNT_ENABLED
201
case JSButton::button_function_t::k_mount_center:
202
camera_mount.set_angle_target(0, 0, 0, false);
203
// for some reason the call to set_angle_targets changes the mode to mavlink targeting!
204
camera_mount.set_mode(MAV_MOUNT_MODE_RC_TARGETING);
205
break;
206
case JSButton::button_function_t::k_mount_tilt_up:
207
cam_tilt = 1900;
208
break;
209
case JSButton::button_function_t::k_mount_tilt_down:
210
cam_tilt = 1100;
211
break;
212
#endif // HAL_MOUNT_ENABLED
213
case JSButton::button_function_t::k_camera_trigger:
214
break;
215
case JSButton::button_function_t::k_camera_source_toggle:
216
if (!held) {
217
static bool video_toggle = false;
218
video_toggle = !video_toggle;
219
if (video_toggle) {
220
SRV_Channels::set_output_scaled(SRV_Channel::k_video_switch, 1000);
221
gcs().send_text(MAV_SEVERITY_INFO,"Video Toggle: Source 2");
222
} else {
223
SRV_Channels::set_output_scaled(SRV_Channel::k_video_switch, 0.0);
224
gcs().send_text(MAV_SEVERITY_INFO,"Video Toggle: Source 1");
225
}
226
}
227
break;
228
#if HAL_MOUNT_ENABLED
229
case JSButton::button_function_t::k_mount_pan_right:
230
cam_pan = 1900;
231
break;
232
case JSButton::button_function_t::k_mount_pan_left:
233
cam_pan = 1100;
234
break;
235
#endif // HAL_MOUNT_ENABLED
236
case JSButton::button_function_t::k_lights1_cycle:
237
if (!held) {
238
static bool increasing = true;
239
uint16_t step = 1000.0 / g.lights_steps;
240
if (increasing) {
241
lights1 = constrain_float(lights1 + step, 0.0, 1000.0);
242
} else {
243
lights1 = constrain_float(lights1 - step, 0.0, 1000.0);
244
}
245
if (lights1 >= 1000.0 || lights1 <= 0.0) {
246
increasing = !increasing;
247
}
248
SRV_Channels::set_output_scaled(SRV_Channel::k_lights1, lights1);
249
}
250
break;
251
case JSButton::button_function_t::k_lights1_brighter:
252
if (!held) {
253
uint16_t step = 1000.0 / g.lights_steps;
254
lights1 = constrain_float(lights1 + step, 0.0, 1000.0);
255
SRV_Channels::set_output_scaled(SRV_Channel::k_lights1, lights1);
256
}
257
break;
258
case JSButton::button_function_t::k_lights1_dimmer:
259
if (!held) {
260
uint16_t step = 1000.0 / g.lights_steps;
261
lights1 = constrain_float(lights1 - step, 0.0, 1000.0);
262
SRV_Channels::set_output_scaled(SRV_Channel::k_lights1, lights1);
263
}
264
break;
265
case JSButton::button_function_t::k_lights2_cycle:
266
if (!held) {
267
static bool increasing = true;
268
uint16_t step = 1000.0 / g.lights_steps;
269
if (increasing) {
270
lights2 = constrain_float(lights2 + step, 0.0, 1000.0);
271
} else {
272
lights2 = constrain_float(lights2 - step, 0.0, 1000.0);
273
}
274
if (lights2 >= 1000.0 || lights2 <= 0.0) {
275
increasing = !increasing;
276
}
277
SRV_Channels::set_output_scaled(SRV_Channel::k_lights2, lights2);
278
}
279
break;
280
case JSButton::button_function_t::k_lights2_brighter:
281
if (!held) {
282
uint16_t step = 1000.0 / g.lights_steps;
283
lights2 = constrain_float(lights2 + step, 0.0, 1000.0);
284
SRV_Channels::set_output_scaled(SRV_Channel::k_lights2, lights2);
285
}
286
break;
287
case JSButton::button_function_t::k_lights2_dimmer:
288
if (!held) {
289
uint16_t step = 1000.0 / g.lights_steps;
290
lights2 = constrain_float(lights2 - step, 0.0, 1000.0);
291
SRV_Channels::set_output_scaled(SRV_Channel::k_lights2, lights2);
292
}
293
break;
294
case JSButton::button_function_t::k_gain_toggle:
295
if (!held) {
296
static bool lowGain = false;
297
lowGain = !lowGain;
298
if (lowGain) {
299
gain = 0.5f;
300
} else {
301
gain = 1.0f;
302
}
303
gcs().send_text(MAV_SEVERITY_INFO,"#Gain: %2.0f%%",(double)gain*100);
304
}
305
break;
306
case JSButton::button_function_t::k_gain_inc:
307
if (!held) {
308
// check that our gain parameters are in correct range, update in eeprom and notify gcs if needed
309
g.minGain.set_and_save(constrain_float(g.minGain, 0.10, 0.80));
310
g.maxGain.set_and_save(constrain_float(g.maxGain, g.minGain, 1.0));
311
g.numGainSettings.set_and_save(constrain_int16(g.numGainSettings, 1, 10));
312
313
if (g.numGainSettings == 1) {
314
gain = constrain_float(g.gain_default, g.minGain, g.maxGain);
315
} else {
316
gain = constrain_float(gain + (g.maxGain-g.minGain)/(g.numGainSettings-1), g.minGain, g.maxGain);
317
}
318
319
gcs().send_text(MAV_SEVERITY_INFO,"#Gain is %2.0f%%",(double)gain*100);
320
}
321
break;
322
case JSButton::button_function_t::k_gain_dec:
323
if (!held) {
324
// check that our gain parameters are in correct range, update in eeprom and notify gcs if needed
325
g.minGain.set_and_save(constrain_float(g.minGain, 0.10, 0.80));
326
g.maxGain.set_and_save(constrain_float(g.maxGain, g.minGain, 1.0));
327
g.numGainSettings.set_and_save(constrain_int16(g.numGainSettings, 1, 10));
328
329
if (g.numGainSettings == 1) {
330
gain = constrain_float(g.gain_default, g.minGain, g.maxGain);
331
} else {
332
gain = constrain_float(gain - (g.maxGain-g.minGain)/(g.numGainSettings-1), g.minGain, g.maxGain);
333
}
334
335
gcs().send_text(MAV_SEVERITY_INFO,"#Gain is %2.0f%%",(double)gain*100);
336
}
337
break;
338
case JSButton::button_function_t::k_trim_roll_inc:
339
rollTrim = constrain_float(rollTrim+10,-200,200);
340
break;
341
case JSButton::button_function_t::k_trim_roll_dec:
342
rollTrim = constrain_float(rollTrim-10,-200,200);
343
break;
344
case JSButton::button_function_t::k_trim_pitch_inc:
345
pitchTrim = constrain_float(pitchTrim+10,-200,200);
346
break;
347
case JSButton::button_function_t::k_trim_pitch_dec:
348
pitchTrim = constrain_float(pitchTrim-10,-200,200);
349
break;
350
case JSButton::button_function_t::k_input_hold_set:
351
if(!motors.armed()) {
352
break;
353
}
354
if (!held) {
355
zTrim = abs(z_last-500) > 50 ? z_last-500 : 0;
356
xTrim = abs(x_last) > 50 ? x_last : 0;
357
yTrim = abs(y_last) > 50 ? y_last : 0;
358
bool input_hold_engaged_last = input_hold_engaged;
359
input_hold_engaged = zTrim || xTrim || yTrim;
360
if (input_hold_engaged) {
361
gcs().send_text(MAV_SEVERITY_INFO,"#Input Hold Set");
362
} else if (input_hold_engaged_last) {
363
gcs().send_text(MAV_SEVERITY_INFO,"#Input Hold Disabled");
364
}
365
controls_reset_since_input_hold = !input_hold_engaged;
366
}
367
break;
368
#if AP_RELAY_ENABLED
369
case JSButton::button_function_t::k_relay_1_on:
370
relay.on(0);
371
break;
372
case JSButton::button_function_t::k_relay_1_off:
373
relay.off(0);
374
break;
375
case JSButton::button_function_t::k_relay_1_toggle:
376
if (!held) {
377
relay.toggle(0);
378
}
379
break;
380
case JSButton::button_function_t::k_relay_1_momentary:
381
if (!held) {
382
relay.on(0);
383
}
384
break;
385
case JSButton::button_function_t::k_relay_2_on:
386
relay.on(1);
387
break;
388
case JSButton::button_function_t::k_relay_2_off:
389
relay.off(1);
390
break;
391
case JSButton::button_function_t::k_relay_2_toggle:
392
if (!held) {
393
relay.toggle(1);
394
}
395
break;
396
case JSButton::button_function_t::k_relay_2_momentary:
397
if (!held) {
398
relay.on(1);
399
}
400
break;
401
case JSButton::button_function_t::k_relay_3_on:
402
relay.on(2);
403
break;
404
case JSButton::button_function_t::k_relay_3_off:
405
relay.off(2);
406
break;
407
case JSButton::button_function_t::k_relay_3_toggle:
408
if (!held) {
409
relay.toggle(2);
410
}
411
break;
412
case JSButton::button_function_t::k_relay_3_momentary:
413
if (!held) {
414
relay.on(2);
415
}
416
break;
417
case JSButton::button_function_t::k_relay_4_on:
418
relay.on(3);
419
break;
420
case JSButton::button_function_t::k_relay_4_off:
421
relay.off(3);
422
break;
423
case JSButton::button_function_t::k_relay_4_toggle:
424
if (!held) {
425
relay.toggle(3);
426
}
427
break;
428
case JSButton::button_function_t::k_relay_4_momentary:
429
if (!held) {
430
relay.on(3);
431
}
432
break;
433
#endif
434
435
////////////////////////////////////////////////
436
// Servo functions
437
#if AP_SERVORELAYEVENTS_ENABLED
438
case JSButton::button_function_t::k_servo_1_inc:
439
sub.g2.actuators.increase_actuator(0);
440
break;
441
case JSButton::button_function_t::k_servo_2_inc:
442
sub.g2.actuators.increase_actuator(1);
443
break;
444
case JSButton::button_function_t::k_servo_3_inc:
445
sub.g2.actuators.increase_actuator(2);
446
break;
447
case JSButton::button_function_t::k_servo_4_inc:
448
sub.g2.actuators.increase_actuator(3);
449
break;
450
case JSButton::button_function_t::k_servo_5_inc:
451
sub.g2.actuators.increase_actuator(4);
452
break;
453
case JSButton::button_function_t::k_servo_6_inc:
454
sub.g2.actuators.increase_actuator(5);
455
break;
456
457
case JSButton::button_function_t::k_servo_1_dec:
458
sub.g2.actuators.decrease_actuator(0);
459
break;
460
case JSButton::button_function_t::k_servo_2_dec:
461
sub.g2.actuators.decrease_actuator(1);
462
break;
463
case JSButton::button_function_t::k_servo_3_dec:
464
sub.g2.actuators.decrease_actuator(2);
465
break;
466
case JSButton::button_function_t::k_servo_4_dec:
467
sub.g2.actuators.decrease_actuator(3);
468
break;
469
case JSButton::button_function_t::k_servo_5_dec:
470
sub.g2.actuators.decrease_actuator(4);
471
break;
472
case JSButton::button_function_t::k_servo_6_dec:
473
sub.g2.actuators.decrease_actuator(5);
474
break;
475
476
case JSButton::button_function_t::k_servo_1_min:
477
case JSButton::button_function_t::k_servo_1_min_momentary:
478
sub.g2.actuators.min_actuator(0);
479
break;
480
case JSButton::button_function_t::k_servo_2_min:
481
case JSButton::button_function_t::k_servo_2_min_momentary:
482
sub.g2.actuators.min_actuator(1);
483
break;
484
case JSButton::button_function_t::k_servo_3_min:
485
case JSButton::button_function_t::k_servo_3_min_momentary:
486
sub.g2.actuators.min_actuator(2);
487
break;
488
case JSButton::button_function_t::k_servo_4_min:
489
case JSButton::button_function_t::k_servo_4_min_momentary:
490
sub.g2.actuators.min_actuator(3);
491
break;
492
case JSButton::button_function_t::k_servo_5_min:
493
case JSButton::button_function_t::k_servo_5_min_momentary:
494
sub.g2.actuators.min_actuator(4);
495
break;
496
case JSButton::button_function_t::k_servo_6_min:
497
case JSButton::button_function_t::k_servo_6_min_momentary:
498
sub.g2.actuators.min_actuator(5);
499
break;
500
501
case JSButton::button_function_t::k_servo_1_min_toggle:
502
if (!held) {
503
sub.g2.actuators.min_toggle_actuator(0);
504
}
505
break;
506
case JSButton::button_function_t::k_servo_2_min_toggle:
507
if (!held) {
508
sub.g2.actuators.min_toggle_actuator(1);
509
}
510
break;
511
case JSButton::button_function_t::k_servo_3_min_toggle:
512
if (!held) {
513
sub.g2.actuators.min_toggle_actuator(2);
514
}
515
break;
516
case JSButton::button_function_t::k_servo_4_min_toggle:
517
if (!held) {
518
sub.g2.actuators.min_toggle_actuator(3);
519
}
520
break;
521
case JSButton::button_function_t::k_servo_5_min_toggle:
522
if (!held) {
523
sub.g2.actuators.min_toggle_actuator(4);
524
}
525
break;
526
case JSButton::button_function_t::k_servo_6_min_toggle:
527
if (!held) {
528
sub.g2.actuators.min_toggle_actuator(5);
529
}
530
break;
531
532
case JSButton::button_function_t::k_servo_1_max:
533
case JSButton::button_function_t::k_servo_1_max_momentary:
534
sub.g2.actuators.max_actuator(0);
535
break;
536
case JSButton::button_function_t::k_servo_2_max:
537
case JSButton::button_function_t::k_servo_2_max_momentary:
538
sub.g2.actuators.max_actuator(1);
539
break;
540
case JSButton::button_function_t::k_servo_3_max:
541
case JSButton::button_function_t::k_servo_3_max_momentary:
542
sub.g2.actuators.max_actuator(2);
543
break;
544
case JSButton::button_function_t::k_servo_4_max:
545
case JSButton::button_function_t::k_servo_4_max_momentary:
546
sub.g2.actuators.max_actuator(3);
547
break;
548
case JSButton::button_function_t::k_servo_5_max:
549
case JSButton::button_function_t::k_servo_5_max_momentary:
550
sub.g2.actuators.max_actuator(4);
551
break;
552
553
case JSButton::button_function_t::k_servo_1_max_toggle:
554
if (!held) {
555
sub.g2.actuators.max_toggle_actuator(0);
556
}
557
break;
558
case JSButton::button_function_t::k_servo_2_max_toggle:
559
if (!held) {
560
sub.g2.actuators.max_toggle_actuator(1);
561
}
562
break;
563
case JSButton::button_function_t::k_servo_3_max_toggle:
564
if (!held) {
565
sub.g2.actuators.max_toggle_actuator(2);
566
}
567
break;
568
case JSButton::button_function_t::k_servo_4_max_toggle:
569
if (!held) {
570
sub.g2.actuators.max_toggle_actuator(3);
571
}
572
break;
573
case JSButton::button_function_t::k_servo_5_max_toggle:
574
if (!held) {
575
sub.g2.actuators.max_toggle_actuator(4);
576
}
577
break;
578
case JSButton::button_function_t::k_servo_6_max_toggle:
579
if (!held) {
580
sub.g2.actuators.max_toggle_actuator(5);
581
}
582
break;
583
584
case JSButton::button_function_t::k_servo_1_center:
585
sub.g2.actuators.center_actuator(0);
586
break;
587
case JSButton::button_function_t::k_servo_2_center:
588
sub.g2.actuators.center_actuator(1);
589
break;
590
case JSButton::button_function_t::k_servo_3_center:
591
sub.g2.actuators.center_actuator(2);
592
break;
593
case JSButton::button_function_t::k_servo_4_center:
594
sub.g2.actuators.center_actuator(3);
595
break;
596
case JSButton::button_function_t::k_servo_5_center:
597
sub.g2.actuators.center_actuator(4);
598
break;
599
case JSButton::button_function_t::k_servo_6_center:
600
sub.g2.actuators.center_actuator(5);
601
break;
602
#endif // AP_SERVORELAYEVENTS_ENABLED
603
604
case JSButton::button_function_t::k_roll_pitch_toggle:
605
if (!held) {
606
roll_pitch_flag = !roll_pitch_flag;
607
if (roll_pitch_flag) {
608
gcs().send_text(MAV_SEVERITY_INFO, "#Attitude Control");
609
}
610
else {
611
gcs().send_text(MAV_SEVERITY_INFO, "#Movement Control");
612
}
613
}
614
break;
615
616
case JSButton::button_function_t::k_custom_1:
617
// Not implemented
618
break;
619
case JSButton::button_function_t::k_custom_2:
620
// Not implemented
621
break;
622
case JSButton::button_function_t::k_custom_3:
623
// Not implemented
624
break;
625
case JSButton::button_function_t::k_custom_4:
626
// Not implemented
627
break;
628
case JSButton::button_function_t::k_custom_5:
629
// Not implemented
630
break;
631
case JSButton::button_function_t::k_custom_6:
632
// Not implemented
633
break;
634
635
#if AP_SCRIPTING_ENABLED
636
case JSButton::button_function_t::k_script_1:
637
sub.script_buttons[0].press();
638
break;
639
case JSButton::button_function_t::k_script_2:
640
sub.script_buttons[1].press();
641
break;
642
case JSButton::button_function_t::k_script_3:
643
sub.script_buttons[2].press();
644
break;
645
case JSButton::button_function_t::k_script_4:
646
sub.script_buttons[3].press();
647
break;
648
#endif // AP_SCRIPTING_ENABLED
649
}
650
}
651
652
void Sub::handle_jsbutton_release(uint8_t _button, bool shift) {
653
654
// Act based on the function assigned to this button
655
switch (get_button(_button)->function(shift)) {
656
#if AP_RELAY_ENABLED
657
case JSButton::button_function_t::k_relay_1_momentary:
658
relay.off(0);
659
break;
660
case JSButton::button_function_t::k_relay_2_momentary:
661
relay.off(1);
662
break;
663
case JSButton::button_function_t::k_relay_3_momentary:
664
relay.off(2);
665
break;
666
case JSButton::button_function_t::k_relay_4_momentary:
667
relay.off(3);
668
break;
669
#endif
670
#if AP_SERVORELAYEVENTS_ENABLED
671
case JSButton::button_function_t::k_servo_1_min_momentary:
672
case JSButton::button_function_t::k_servo_1_max_momentary:
673
{
674
sub.g2.actuators.center_actuator(0);
675
}
676
break;
677
case JSButton::button_function_t::k_servo_2_min_momentary:
678
case JSButton::button_function_t::k_servo_2_max_momentary:
679
{
680
sub.g2.actuators.center_actuator(1);
681
}
682
break;
683
case JSButton::button_function_t::k_servo_3_min_momentary:
684
case JSButton::button_function_t::k_servo_3_max_momentary:
685
{
686
sub.g2.actuators.center_actuator(2);
687
}
688
break;
689
case JSButton::button_function_t::k_servo_4_min_momentary:
690
case JSButton::button_function_t::k_servo_4_max_momentary:
691
{
692
sub.g2.actuators.center_actuator(3);
693
}
694
break;
695
case JSButton::button_function_t::k_servo_5_min_momentary:
696
case JSButton::button_function_t::k_servo_5_max_momentary:
697
{
698
sub.g2.actuators.center_actuator(4);
699
}
700
break;
701
case JSButton::button_function_t::k_servo_6_min_momentary:
702
case JSButton::button_function_t::k_servo_6_max_momentary:
703
{
704
sub.g2.actuators.center_actuator(5);
705
}
706
break;
707
#endif
708
709
#if AP_SCRIPTING_ENABLED
710
case JSButton::button_function_t::k_script_1:
711
sub.script_buttons[0].release();
712
break;
713
case JSButton::button_function_t::k_script_2:
714
sub.script_buttons[1].release();
715
break;
716
case JSButton::button_function_t::k_script_3:
717
sub.script_buttons[2].release();
718
break;
719
case JSButton::button_function_t::k_script_4:
720
sub.script_buttons[3].release();
721
break;
722
#endif // AP_SCRIPTING_ENABLED
723
}
724
}
725
726
JSButton* Sub::get_button(uint8_t index)
727
{
728
// Help to access appropriate parameter
729
switch (index) {
730
case 0:
731
return &g.jbtn_0;
732
case 1:
733
return &g.jbtn_1;
734
case 2:
735
return &g.jbtn_2;
736
case 3:
737
return &g.jbtn_3;
738
case 4:
739
return &g.jbtn_4;
740
case 5:
741
return &g.jbtn_5;
742
case 6:
743
return &g.jbtn_6;
744
case 7:
745
return &g.jbtn_7;
746
case 8:
747
return &g.jbtn_8;
748
case 9:
749
return &g.jbtn_9;
750
case 10:
751
return &g.jbtn_10;
752
case 11:
753
return &g.jbtn_11;
754
case 12:
755
return &g.jbtn_12;
756
case 13:
757
return &g.jbtn_13;
758
case 14:
759
return &g.jbtn_14;
760
case 15:
761
return &g.jbtn_15;
762
763
// add 16 more cases for 32 buttons with MANUAL_CONTROL extensions
764
case 16:
765
return &g.jbtn_16;
766
case 17:
767
return &g.jbtn_17;
768
case 18:
769
return &g.jbtn_18;
770
case 19:
771
return &g.jbtn_19;
772
case 20:
773
return &g.jbtn_20;
774
case 21:
775
return &g.jbtn_21;
776
case 22:
777
return &g.jbtn_22;
778
case 23:
779
return &g.jbtn_23;
780
case 24:
781
return &g.jbtn_24;
782
case 25:
783
return &g.jbtn_25;
784
case 26:
785
return &g.jbtn_26;
786
case 27:
787
return &g.jbtn_27;
788
case 28:
789
return &g.jbtn_28;
790
case 29:
791
return &g.jbtn_29;
792
case 30:
793
return &g.jbtn_30;
794
case 31:
795
return &g.jbtn_31;
796
default:
797
return &g.jbtn_0;
798
}
799
}
800
801
void Sub::default_js_buttons()
802
{
803
JSButton::button_function_t defaults[16][2] = {
804
{JSButton::button_function_t::k_none, JSButton::button_function_t::k_none},
805
{JSButton::button_function_t::k_mode_manual, JSButton::button_function_t::k_none},
806
{JSButton::button_function_t::k_mode_depth_hold, JSButton::button_function_t::k_none},
807
{JSButton::button_function_t::k_mode_stabilize, JSButton::button_function_t::k_none},
808
809
{JSButton::button_function_t::k_disarm, JSButton::button_function_t::k_none},
810
{JSButton::button_function_t::k_shift, JSButton::button_function_t::k_none},
811
{JSButton::button_function_t::k_arm, JSButton::button_function_t::k_none},
812
{JSButton::button_function_t::k_mount_center, JSButton::button_function_t::k_none},
813
814
{JSButton::button_function_t::k_input_hold_set, JSButton::button_function_t::k_none},
815
{JSButton::button_function_t::k_mount_tilt_down, JSButton::button_function_t::k_mount_pan_left},
816
{JSButton::button_function_t::k_mount_tilt_up, JSButton::button_function_t::k_mount_pan_right},
817
{JSButton::button_function_t::k_gain_inc, JSButton::button_function_t::k_trim_pitch_dec},
818
819
{JSButton::button_function_t::k_gain_dec, JSButton::button_function_t::k_trim_pitch_inc},
820
{JSButton::button_function_t::k_lights1_dimmer, JSButton::button_function_t::k_trim_roll_dec},
821
{JSButton::button_function_t::k_lights1_brighter, JSButton::button_function_t::k_trim_roll_inc},
822
{JSButton::button_function_t::k_none, JSButton::button_function_t::k_none},
823
};
824
825
for (int i = 0; i < 16; i++) {
826
get_button(i)->set_default(defaults[i][0], defaults[i][1]);
827
}
828
}
829
830
void Sub::set_neutral_controls()
831
{
832
channel_roll->set_radio_in(channel_roll->get_radio_trim());
833
channel_pitch->set_radio_in(channel_pitch->get_radio_trim());
834
channel_yaw->set_radio_in(channel_yaw->get_radio_trim());
835
channel_throttle->set_radio_in(channel_throttle->get_radio_trim());
836
channel_forward->set_radio_in(channel_forward->get_radio_trim());
837
channel_lateral->set_radio_in(channel_lateral->get_radio_trim());
838
839
// Clear pitch/roll trim settings
840
pitchTrim = 0;
841
rollTrim = 0;
842
}
843
844
void Sub::clear_input_hold()
845
{
846
xTrim = 0;
847
yTrim = 0;
848
zTrim = 0;
849
input_hold_engaged = false;
850
}
851
852
#if AP_SCRIPTING_ENABLED
853
bool Sub::is_button_pressed(uint8_t index)
854
{
855
return script_buttons[index - 1].is_pressed();
856
}
857
858
uint8_t Sub::get_and_clear_button_count(uint8_t index)
859
{
860
return script_buttons[index - 1].get_and_clear_count();
861
}
862
#endif // AP_SCRIPTING_ENABLED
863
864