CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Button/AP_Button.cpp
Views: 1798
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
AP_GROUPINFO("PIN1", 1, AP_Button, pin[0], -1),
47
48
// @Param: PIN2
49
// @DisplayName: Second button Pin
50
// @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.
51
// @User: Standard
52
// @Values: -1:Disabled,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6
53
AP_GROUPINFO("PIN2", 2, AP_Button, pin[1], -1),
54
55
// @Param: PIN3
56
// @DisplayName: Third button Pin
57
// @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.
58
// @User: Standard
59
// @Values: -1:Disabled,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6
60
AP_GROUPINFO("PIN3", 3, AP_Button, pin[2], -1),
61
62
// @Param: PIN4
63
// @DisplayName: Fourth button Pin
64
// @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.
65
// @User: Standard
66
// @Values: -1:Disabled,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6
67
AP_GROUPINFO("PIN4", 4, AP_Button, pin[3], -1),
68
69
// @Param: REPORT_SEND
70
// @DisplayName: Report send time
71
// @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.
72
// @User: Standard
73
// @Range: 0 3600
74
AP_GROUPINFO("REPORT_SEND", 5, AP_Button, report_send_time, 10),
75
76
// @Param: OPTIONS1
77
// @DisplayName: Button Pin 1 Options
78
// @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.
79
// @User: Standard
80
// @Bitmask: 0:PWM Input,1:InvertInput
81
AP_GROUPINFO("OPTIONS1", 6, AP_Button, options[0], 0),
82
83
// @Param: OPTIONS2
84
// @DisplayName: Button Pin 2 Options
85
// @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.
86
// @User: Standard
87
// @Bitmask: 0:PWM Input,1:InvertInput
88
AP_GROUPINFO("OPTIONS2", 7, AP_Button, options[1], 0),
89
90
// @Param: OPTIONS3
91
// @DisplayName: Button Pin 3 Options
92
// @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.
93
// @Bitmask: 0:PWM Input,1:InvertInput
94
AP_GROUPINFO("OPTIONS3", 8, AP_Button, options[2], 0),
95
96
// @Param: OPTIONS4
97
// @DisplayName: Button Pin 4 Options
98
// @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.
99
// @User: Standard
100
// @Bitmask: 0:PWM Input,1:InvertInput
101
AP_GROUPINFO("OPTIONS4", 9, AP_Button, options[3], 0),
102
103
// @Param: FUNC1
104
// @CopyFieldsFrom: RC1_OPTION
105
// @DisplayName: Button Pin 1 RC Channel function
106
// @Description: Auxiliary RC Options function executed on pin change
107
// @User: Standard
108
AP_GROUPINFO("FUNC1", 10, AP_Button, pin_func[0], (uint16_t)RC_Channel::AUX_FUNC::DO_NOTHING),
109
110
// @Param: FUNC2
111
// @CopyFieldsFrom: BTN_FUNC1
112
// @DisplayName: Button Pin 2 RC Channel function
113
AP_GROUPINFO("FUNC2", 11, AP_Button, pin_func[1], (uint16_t)RC_Channel::AUX_FUNC::DO_NOTHING),
114
115
// @Param: FUNC3
116
// @CopyFieldsFrom: BTN_FUNC1
117
// @DisplayName: Button Pin 3 RC Channel function
118
AP_GROUPINFO("FUNC3", 12, AP_Button, pin_func[2], (uint16_t)RC_Channel::AUX_FUNC::DO_NOTHING),
119
120
// @Param: FUNC4
121
// @CopyFieldsFrom: BTN_FUNC1
122
// @DisplayName: Button Pin 4 RC Channel function
123
AP_GROUPINFO("FUNC4", 13, AP_Button, pin_func[3], (uint16_t)RC_Channel::AUX_FUNC::DO_NOTHING),
124
125
AP_GROUPEND
126
};
127
128
129
// constructor
130
AP_Button::AP_Button(void)
131
{
132
AP_Param::setup_object_defaults(this, var_info);
133
134
if (_singleton != nullptr) {
135
AP_HAL::panic("AP_Button must be singleton");
136
}
137
_singleton = this;
138
}
139
140
/*
141
update and report, called from main loop
142
*/
143
void AP_Button::update(void)
144
{
145
if (!enable) {
146
return;
147
}
148
149
// call setup pins at update rate (5Hz) to allow for runtime parameter change of pins
150
setup_pins();
151
152
if (!initialised) {
153
initialised = true;
154
155
// get initial mask
156
last_mask = get_mask();
157
debounce_mask = last_mask;
158
159
// register 1kHz timer callback
160
hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&AP_Button::timer_update, void));
161
}
162
163
// act on any changes in state
164
{
165
WITH_SEMAPHORE(last_debounced_change_ms_sem);
166
if (last_debounced_change_ms > last_debounce_ms) {
167
last_debounce_ms = last_debounced_change_ms;
168
}
169
}
170
171
// update the PWM state:
172
uint8_t new_pwm_state = pwm_state;
173
for (uint8_t i=0; i<AP_BUTTON_NUM_PINS; i++) {
174
const uint8_t mask = (1U << i);
175
if (!is_pwm_input(i)) {
176
// not a PWM input
177
new_pwm_state &= ~mask;
178
continue;
179
}
180
const uint16_t pwm_us = pwm_pin_source[i].get_pwm_us();
181
if (pwm_us < RC_Channel::RC_MIN_LIMIT_PWM || pwm_us > RC_Channel::RC_MAX_LIMIT_PWM) {
182
// invalid pulse width, trigger low
183
if (pwm_state & mask) {
184
new_pwm_state &= ~mask;
185
}
186
continue;
187
}
188
// these values are the same as used in RC_Channel:
189
if (pwm_state & mask) {
190
// currently asserted; check to see if we should de-assert
191
if (pwm_us < RC_Channel::AUX_SWITCH_PWM_TRIGGER_LOW) {
192
new_pwm_state &= ~mask;
193
}
194
} else {
195
// currently not asserted; check to see if we should assert
196
if (pwm_us > RC_Channel::AUX_SWITCH_PWM_TRIGGER_HIGH) {
197
new_pwm_state |= mask;
198
}
199
}
200
}
201
const uint64_t now_ms = AP_HAL::millis64();
202
if (new_pwm_state != pwm_state) {
203
if (new_pwm_state != tentative_pwm_state) {
204
tentative_pwm_state = new_pwm_state;
205
pwm_start_debounce_ms = now_ms;
206
} else if (now_ms - pwm_start_debounce_ms > DEBOUNCE_MS) {
207
pwm_state = new_pwm_state;
208
last_debounce_ms = now_ms;
209
}
210
} else {
211
tentative_pwm_state = pwm_state;
212
pwm_start_debounce_ms = now_ms;
213
}
214
215
#if HAL_GCS_ENABLED
216
if (last_debounce_ms != 0 &&
217
(AP_HAL::millis() - last_report_ms) > AP_BUTTON_REPORT_PERIOD_MS &&
218
(AP_HAL::millis64() - last_debounce_ms) < report_send_time*1000ULL) {
219
// send a change report
220
last_report_ms = AP_HAL::millis();
221
222
// send a report to GCS
223
send_report();
224
}
225
#endif
226
227
if (!aux_functions_initialised) {
228
run_aux_functions(true);
229
aux_functions_initialised = true;
230
}
231
232
if (last_debounce_ms != 0 &&
233
last_debounce_ms != last_action_time_ms) {
234
last_action_time_ms = last_debounce_ms;
235
run_aux_functions(false);
236
}
237
}
238
239
void AP_Button::run_aux_functions(bool force)
240
{
241
RC_Channel *rc_channel = rc().channel(1);
242
if (rc_channel == nullptr) {
243
return;
244
}
245
246
for (uint8_t i=0; i<AP_BUTTON_NUM_PINS; i++) {
247
const RC_Channel::AUX_FUNC func = RC_Channel::AUX_FUNC(pin_func[i].get());
248
if (func == RC_Channel::AUX_FUNC::DO_NOTHING) {
249
continue;
250
}
251
const uint8_t value_mask = (1U<<i);
252
bool value;
253
if (is_pwm_input(i)) {
254
value = (pwm_state & value_mask) != 0;
255
} else {
256
value = (debounce_mask & value_mask) != 0;
257
}
258
if (is_input_inverted(i)) {
259
value = !value;
260
}
261
const bool actioned = ((state_actioned_mask & value_mask) != 0);
262
if (!force && value == actioned) {
263
// no change on this pin
264
continue;
265
}
266
// mark action as done:
267
if (value) {
268
state_actioned_mask |= value_mask;
269
} else {
270
state_actioned_mask &= ~value_mask;
271
}
272
273
const RC_Channel::AuxSwitchPos pos = value ? RC_Channel::AuxSwitchPos::HIGH : RC_Channel::AuxSwitchPos::LOW;
274
// I wonder if we can do better here:
275
#if AP_RC_CHANNEL_AUX_FUNCTION_STRINGS_ENABLED
276
const char *str = rc_channel->string_for_aux_function(func);
277
if (str != nullptr) {
278
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Button %i: executing (%s %s)", i+1, str, rc_channel->string_for_aux_pos(pos));
279
}
280
#endif
281
rc_channel->run_aux_function(func, pos, RC_Channel::AuxFuncTrigger::Source::BUTTON, i);
282
}
283
}
284
285
// get state of a button
286
// used by scripting
287
bool AP_Button::get_button_state(uint8_t number)
288
{
289
// pins params are 1 indexed not zero
290
if (number == 0 || number > AP_BUTTON_NUM_PINS) {
291
return false;
292
}
293
294
if (is_pwm_input(number-1)) {
295
return (pwm_state & (1U<<(number-1)));
296
}
297
298
return ( ((1 << (number - 1)) & debounce_mask) != 0);
299
};
300
301
/*
302
get current mask
303
*/
304
uint8_t AP_Button::get_mask(void)
305
{
306
uint8_t mask = 0;
307
for (uint8_t i=0; i<AP_BUTTON_NUM_PINS; i++) {
308
if (pin[i] == -1) {
309
continue;
310
}
311
if (is_pwm_input(i)) {
312
continue;
313
}
314
mask |= hal.gpio->read(pin[i]) << i;
315
}
316
317
return mask;
318
}
319
320
/*
321
called at 1kHz to check for button state change
322
*/
323
void AP_Button::timer_update(void)
324
{
325
if (!enable) {
326
return;
327
}
328
uint8_t mask = get_mask();
329
uint64_t now = AP_HAL::millis64();
330
if (mask != last_mask) {
331
last_mask = mask;
332
last_change_time_ms = now;
333
}
334
if (debounce_mask != last_mask &&
335
(now - last_change_time_ms) > DEBOUNCE_MS) {
336
// crude de-bouncing, debounces all buttons as one, not individually
337
debounce_mask = last_mask;
338
WITH_SEMAPHORE(last_debounced_change_ms_sem);
339
last_debounced_change_ms = now;
340
}
341
}
342
343
#if HAL_GCS_ENABLED
344
/*
345
send a BUTTON_CHANGE report to the GCS
346
*/
347
void AP_Button::send_report(void) const
348
{
349
const uint8_t mask = last_mask | pwm_state;
350
const mavlink_button_change_t packet{
351
time_boot_ms: AP_HAL::millis(),
352
last_change_ms: uint32_t(last_debounce_ms),
353
state: mask,
354
};
355
gcs().send_to_active_channels(MAVLINK_MSG_ID_BUTTON_CHANGE,
356
(const char *)&packet);
357
}
358
#endif
359
360
/*
361
setup the pins as input with pullup. We need pullup to give reliable
362
input with a pulldown button
363
*/
364
void AP_Button::setup_pins(void)
365
{
366
for (uint8_t i=0; i<AP_BUTTON_NUM_PINS; i++) {
367
if (is_pwm_input(i)) {
368
pwm_pin_source[i].set_pin(pin[i], "Button");
369
continue;
370
}
371
if (pin[i] == -1) {
372
continue;
373
}
374
375
hal.gpio->pinMode(pin[i], HAL_GPIO_INPUT);
376
// setup pullup
377
hal.gpio->write(pin[i], 1);
378
}
379
}
380
381
// check settings are valid
382
bool AP_Button::arming_checks(size_t buflen, char *buffer) const
383
{
384
if (!enable) {
385
return true;
386
}
387
for (uint8_t i=0; i<AP_BUTTON_NUM_PINS; i++) {
388
if (pin[i] != -1 && !hal.gpio->valid_pin(pin[i])) {
389
uint8_t servo_ch;
390
if (hal.gpio->pin_to_servo_channel(pin[i], servo_ch)) {
391
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));
392
} else {
393
hal.util->snprintf(buffer, buflen, "BTN_PIN%u=%d invalid", unsigned(i + 1), int(pin[i].get()));
394
}
395
return false;
396
}
397
}
398
return true;
399
}
400
401
namespace AP {
402
403
AP_Button &button()
404
{
405
return *AP_Button::get_singleton();
406
}
407
408
}
409
410
#endif
411
412