Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Button/AP_Button.cpp
9446 views
1
/*
2
This program is free software: you can redistribute it and/or modify
3
it under the terms of the GNU General Public License as published by
4
the Free Software Foundation, either version 3 of the License, or
5
(at your option) any later version.
6
7
This program is distributed in the hope that it will be useful,
8
but WITHOUT ANY WARRANTY; without even the implied warranty of
9
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10
GNU General Public License for more details.
11
12
You should have received a copy of the GNU General Public License
13
along with this program. If not, see <http://www.gnu.org/licenses/>.
14
*/
15
16
17
#include "AP_Button.h"
18
19
#if HAL_BUTTON_ENABLED
20
21
#include <GCS_MAVLink/GCS_MAVLink.h>
22
#include <GCS_MAVLink/GCS.h>
23
#include <RC_Channel/RC_Channel.h>
24
25
// very crude debounce method
26
#define DEBOUNCE_MS 50
27
28
extern const AP_HAL::HAL& hal;
29
30
AP_Button *AP_Button::_singleton;
31
32
const AP_Param::GroupInfo AP_Button::var_info[] = {
33
34
// @Param: ENABLE
35
// @DisplayName: Enable button reporting
36
// @Description: This enables the button checking module. When this is disabled the parameters for setting button inputs are not visible
37
// @Values: 0:Disabled, 1:Enabled
38
// @User: Advanced
39
AP_GROUPINFO_FLAGS("ENABLE", 0, AP_Button, enable, 0, AP_PARAM_FLAG_ENABLE),
40
41
// @Param: PIN1
42
// @DisplayName: First button Pin
43
// @Description: Digital pin number for first button input. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot.
44
// @User: Standard
45
// @Values: -1:Disabled,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6
46
// @Range: -1 127
47
AP_GROUPINFO("PIN1", 1, AP_Button, pin[0], -1),
48
49
// @Param: PIN2
50
// @DisplayName: Second button Pin
51
// @Description: Digital pin number for second button input. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot.
52
// @User: Standard
53
// @Values: -1:Disabled,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6
54
// @Range: -1 127
55
AP_GROUPINFO("PIN2", 2, AP_Button, pin[1], -1),
56
57
// @Param: PIN3
58
// @DisplayName: Third button Pin
59
// @Description: Digital pin number for third button input. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot.
60
// @User: Standard
61
// @Values: -1:Disabled,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6
62
// @Range: -1 127
63
AP_GROUPINFO("PIN3", 3, AP_Button, pin[2], -1),
64
65
// @Param: PIN4
66
// @DisplayName: Fourth button Pin
67
// @Description: Digital pin number for fourth button input. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot.
68
// @User: Standard
69
// @Values: -1:Disabled,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6
70
// @Range: -1 127
71
AP_GROUPINFO("PIN4", 4, AP_Button, pin[3], -1),
72
73
// @Param: REPORT_SEND
74
// @DisplayName: Report send time
75
// @Description: The duration in seconds that a BUTTON_CHANGE report is repeatedly sent to the GCS regarding a button changing state. Note that the BUTTON_CHANGE message is MAVLink2 only.
76
// @User: Standard
77
// @Range: 0 3600
78
AP_GROUPINFO("REPORT_SEND", 5, AP_Button, report_send_time, 10),
79
80
// @Param: OPTIONS1
81
// @DisplayName: Button Pin 1 Options
82
// @Description: Options for Pin 1. PWM input detects PWM above or below 1800/1200us instead of logic level. If PWM is not detected or is less than 800us or above 2200us the button will interpreted as low. Invert changes HIGH state to be logic low voltage on pin, or below 1200us, if PWM input.
83
// @User: Standard
84
// @Bitmask: 0:PWM Input,1:InvertInput
85
AP_GROUPINFO("OPTIONS1", 6, AP_Button, options[0], 0),
86
87
// @Param: OPTIONS2
88
// @DisplayName: Button Pin 2 Options
89
// @Description: Options for Pin 2. PWM input detects PWM above or below 1800/1200us instead of logic level. If PWM is not detected or is less than 800us or above 2200us the button will interpreted as low. Invert changes HIGH state to be logic low voltage on pin, or below 1200us, if PWM input.
90
// @User: Standard
91
// @Bitmask: 0:PWM Input,1:InvertInput
92
AP_GROUPINFO("OPTIONS2", 7, AP_Button, options[1], 0),
93
94
// @Param: OPTIONS3
95
// @DisplayName: Button Pin 3 Options
96
// @Description: Options for Pin 3. PWM input detects PWM above or below 1800/1200us instead of logic level. If PWM is not detected or is less than 800us or above 2200us the button will interpreted as low. Invert changes HIGH state to be logic low voltage on pin, or below 1200us, if PWM input.
97
// @Bitmask: 0:PWM Input,1:InvertInput
98
AP_GROUPINFO("OPTIONS3", 8, AP_Button, options[2], 0),
99
100
// @Param: OPTIONS4
101
// @DisplayName: Button Pin 4 Options
102
// @Description: Options for Pin 4. PWM input detects PWM above or below 1800/1200us instead of logic level. If PWM is not detected or is less than 800us or above 2200us the button will interpreted as low. Invert changes HIGH state to be logic low voltage on pin, or below 1200us, if PWM input.
103
// @User: Standard
104
// @Bitmask: 0:PWM Input,1:InvertInput
105
AP_GROUPINFO("OPTIONS4", 9, AP_Button, options[3], 0),
106
107
// @Param: FUNC1
108
// @CopyFieldsFrom: RC1_OPTION
109
// @DisplayName: Button Pin 1 RC Channel function
110
// @Description: Auxiliary RC Options function executed on pin change
111
// @User: Standard
112
AP_GROUPINFO("FUNC1", 10, AP_Button, pin_func[0], (uint16_t)RC_Channel::AUX_FUNC::DO_NOTHING),
113
114
// @Param: FUNC2
115
// @CopyFieldsFrom: BTN_FUNC1
116
// @DisplayName: Button Pin 2 RC Channel function
117
AP_GROUPINFO("FUNC2", 11, AP_Button, pin_func[1], (uint16_t)RC_Channel::AUX_FUNC::DO_NOTHING),
118
119
// @Param: FUNC3
120
// @CopyFieldsFrom: BTN_FUNC1
121
// @DisplayName: Button Pin 3 RC Channel function
122
AP_GROUPINFO("FUNC3", 12, AP_Button, pin_func[2], (uint16_t)RC_Channel::AUX_FUNC::DO_NOTHING),
123
124
// @Param: FUNC4
125
// @CopyFieldsFrom: BTN_FUNC1
126
// @DisplayName: Button Pin 4 RC Channel function
127
AP_GROUPINFO("FUNC4", 13, AP_Button, pin_func[3], (uint16_t)RC_Channel::AUX_FUNC::DO_NOTHING),
128
129
AP_GROUPEND
130
};
131
132
133
// constructor
134
AP_Button::AP_Button(void)
135
{
136
AP_Param::setup_object_defaults(this, var_info);
137
138
if (_singleton != nullptr) {
139
AP_HAL::panic("AP_Button must be singleton");
140
}
141
_singleton = this;
142
}
143
144
/*
145
update and report, called from main loop
146
*/
147
void AP_Button::update(void)
148
{
149
if (!enable) {
150
return;
151
}
152
153
// call setup pins at update rate (5Hz) to allow for runtime parameter change of pins
154
setup_pins();
155
156
if (!initialised) {
157
initialised = true;
158
159
// get initial mask
160
last_mask = get_mask();
161
debounce_mask = last_mask;
162
163
// register 1kHz timer callback
164
hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&AP_Button::timer_update, void));
165
}
166
167
// act on any changes in state
168
{
169
WITH_SEMAPHORE(last_debounced_change_ms_sem);
170
if (last_debounced_change_ms > last_debounce_ms) {
171
last_debounce_ms = last_debounced_change_ms;
172
}
173
}
174
175
// update the PWM state:
176
uint8_t new_pwm_state = pwm_state;
177
for (uint8_t i=0; i<AP_BUTTON_NUM_PINS; i++) {
178
const uint8_t mask = (1U << i);
179
if (!is_pwm_input(i)) {
180
// not a PWM input
181
new_pwm_state &= ~mask;
182
continue;
183
}
184
const uint16_t pwm_us = pwm_pin_source[i].get_pwm_us();
185
if (pwm_us < RC_Channel::RC_MIN_LIMIT_PWM || pwm_us > RC_Channel::RC_MAX_LIMIT_PWM) {
186
// invalid pulse width, trigger low
187
if (pwm_state & mask) {
188
new_pwm_state &= ~mask;
189
}
190
continue;
191
}
192
// these values are the same as used in RC_Channel:
193
if (pwm_state & mask) {
194
// currently asserted; check to see if we should de-assert
195
if (pwm_us < RC_Channel::AUX_SWITCH_PWM_TRIGGER_LOW) {
196
new_pwm_state &= ~mask;
197
}
198
} else {
199
// currently not asserted; check to see if we should assert
200
if (pwm_us > RC_Channel::AUX_SWITCH_PWM_TRIGGER_HIGH) {
201
new_pwm_state |= mask;
202
}
203
}
204
}
205
const uint64_t now_ms = AP_HAL::millis64();
206
if (new_pwm_state != pwm_state) {
207
if (new_pwm_state != tentative_pwm_state) {
208
tentative_pwm_state = new_pwm_state;
209
pwm_start_debounce_ms = now_ms;
210
} else if (now_ms - pwm_start_debounce_ms > DEBOUNCE_MS) {
211
pwm_state = new_pwm_state;
212
last_debounce_ms = now_ms;
213
}
214
} else {
215
tentative_pwm_state = pwm_state;
216
pwm_start_debounce_ms = now_ms;
217
}
218
219
#if HAL_GCS_ENABLED
220
if (last_debounce_ms != 0 &&
221
(AP_HAL::millis() - last_report_ms) > AP_BUTTON_REPORT_PERIOD_MS &&
222
(AP_HAL::millis64() - last_debounce_ms) < report_send_time*1000ULL) {
223
// send a change report
224
last_report_ms = AP_HAL::millis();
225
226
// send a report to GCS
227
send_report();
228
}
229
#endif
230
231
if (!aux_functions_initialised) {
232
run_aux_functions(true);
233
aux_functions_initialised = true;
234
}
235
236
if (last_debounce_ms != 0 &&
237
last_debounce_ms != last_action_time_ms) {
238
last_action_time_ms = last_debounce_ms;
239
run_aux_functions(false);
240
}
241
}
242
243
void AP_Button::run_aux_functions(bool force)
244
{
245
RC_Channel *rc_channel = rc().channel(1);
246
if (rc_channel == nullptr) {
247
return;
248
}
249
250
for (uint8_t i=0; i<AP_BUTTON_NUM_PINS; i++) {
251
const RC_Channel::AUX_FUNC func = RC_Channel::AUX_FUNC(pin_func[i].get());
252
if (func == RC_Channel::AUX_FUNC::DO_NOTHING) {
253
continue;
254
}
255
const uint8_t value_mask = (1U<<i);
256
bool value;
257
if (is_pwm_input(i)) {
258
value = (pwm_state & value_mask) != 0;
259
} else {
260
value = (debounce_mask & value_mask) != 0;
261
}
262
if (is_input_inverted(i)) {
263
value = !value;
264
}
265
const bool actioned = ((state_actioned_mask & value_mask) != 0);
266
if (!force && value == actioned) {
267
// no change on this pin
268
continue;
269
}
270
// mark action as done:
271
if (value) {
272
state_actioned_mask |= value_mask;
273
} else {
274
state_actioned_mask &= ~value_mask;
275
}
276
277
const RC_Channel::AuxSwitchPos pos = value ? RC_Channel::AuxSwitchPos::HIGH : RC_Channel::AuxSwitchPos::LOW;
278
// I wonder if we can do better here:
279
#if AP_RC_CHANNEL_AUX_FUNCTION_STRINGS_ENABLED
280
const char *str = rc_channel->string_for_aux_function(func);
281
if (str != nullptr) {
282
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Button %i: executing (%s %s)", i+1, str, rc_channel->string_for_aux_pos(pos));
283
}
284
#endif
285
rc_channel->run_aux_function(func, pos, RC_Channel::AuxFuncTrigger::Source::BUTTON, i);
286
}
287
}
288
289
// get state of a button
290
// used by scripting
291
bool AP_Button::get_button_state(uint8_t number)
292
{
293
// pins params are 1 indexed not zero
294
if (number == 0 || number > AP_BUTTON_NUM_PINS) {
295
return false;
296
}
297
298
if (is_pwm_input(number-1)) {
299
return (pwm_state & (1U<<(number-1)));
300
}
301
302
return ( ((1 << (number - 1)) & debounce_mask) != 0);
303
};
304
305
/*
306
get current mask
307
*/
308
uint8_t AP_Button::get_mask(void)
309
{
310
uint8_t mask = 0;
311
for (uint8_t i=0; i<AP_BUTTON_NUM_PINS; i++) {
312
if (pin[i] == -1) {
313
continue;
314
}
315
if (is_pwm_input(i)) {
316
continue;
317
}
318
mask |= hal.gpio->read(pin[i]) << i;
319
}
320
321
return mask;
322
}
323
324
/*
325
called at 1kHz to check for button state change
326
*/
327
void AP_Button::timer_update(void)
328
{
329
if (!enable) {
330
return;
331
}
332
uint8_t mask = get_mask();
333
uint64_t now = AP_HAL::millis64();
334
if (mask != last_mask) {
335
last_mask = mask;
336
last_change_time_ms = now;
337
}
338
if (debounce_mask != last_mask &&
339
(now - last_change_time_ms) > DEBOUNCE_MS) {
340
// crude de-bouncing, debounces all buttons as one, not individually
341
debounce_mask = last_mask;
342
WITH_SEMAPHORE(last_debounced_change_ms_sem);
343
last_debounced_change_ms = now;
344
}
345
}
346
347
#if HAL_GCS_ENABLED
348
/*
349
send a BUTTON_CHANGE report to the GCS
350
*/
351
void AP_Button::send_report(void) const
352
{
353
const uint8_t mask = last_mask | pwm_state;
354
const mavlink_button_change_t packet{
355
time_boot_ms: AP_HAL::millis(),
356
last_change_ms: uint32_t(last_debounce_ms),
357
state: mask,
358
};
359
gcs().send_to_active_channels(MAVLINK_MSG_ID_BUTTON_CHANGE,
360
(const char *)&packet);
361
}
362
#endif
363
364
/*
365
setup the pins as input with pullup. We need pullup to give reliable
366
input with a pulldown button
367
*/
368
void AP_Button::setup_pins(void)
369
{
370
for (uint8_t i=0; i<AP_BUTTON_NUM_PINS; i++) {
371
if (is_pwm_input(i)) {
372
pwm_pin_source[i].set_pin(pin[i], "Button");
373
continue;
374
}
375
if (pin[i] == -1) {
376
continue;
377
}
378
379
hal.gpio->pinMode(pin[i], HAL_GPIO_INPUT);
380
// setup pullup
381
hal.gpio->write(pin[i], 1);
382
}
383
}
384
385
// check settings are valid
386
bool AP_Button::arming_checks(size_t buflen, char *buffer) const
387
{
388
if (!enable) {
389
return true;
390
}
391
for (uint8_t i=0; i<AP_BUTTON_NUM_PINS; i++) {
392
if (pin[i] != -1 && !hal.gpio->valid_pin(pin[i])) {
393
uint8_t servo_ch;
394
if (hal.gpio->pin_to_servo_channel(pin[i], servo_ch)) {
395
hal.util->snprintf(buffer, buflen, "BTN_PIN%u=%d, set SERVO%u_FUNCTION=-1", unsigned(i + 1), int(pin[i].get()), unsigned(servo_ch+1));
396
} else {
397
hal.util->snprintf(buffer, buflen, "BTN_PIN%u=%d invalid", unsigned(i + 1), int(pin[i].get()));
398
}
399
return false;
400
}
401
}
402
return true;
403
}
404
405
namespace AP {
406
407
AP_Button &button()
408
{
409
return *AP_Button::get_singleton();
410
}
411
412
}
413
414
#endif
415
416