Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_Button/AP_Button.cpp
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/141516#include "AP_Button.h"1718#if HAL_BUTTON_ENABLED1920#include <GCS_MAVLink/GCS_MAVLink.h>21#include <GCS_MAVLink/GCS.h>22#include <RC_Channel/RC_Channel.h>2324// very crude debounce method25#define DEBOUNCE_MS 502627extern const AP_HAL::HAL& hal;2829AP_Button *AP_Button::_singleton;3031const AP_Param::GroupInfo AP_Button::var_info[] = {3233// @Param: ENABLE34// @DisplayName: Enable button reporting35// @Description: This enables the button checking module. When this is disabled the parameters for setting button inputs are not visible36// @Values: 0:Disabled, 1:Enabled37// @User: Advanced38AP_GROUPINFO_FLAGS("ENABLE", 0, AP_Button, enable, 0, AP_PARAM_FLAG_ENABLE),3940// @Param: PIN141// @DisplayName: First button Pin42// @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.43// @User: Standard44// @Values: -1:Disabled,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT645AP_GROUPINFO("PIN1", 1, AP_Button, pin[0], -1),4647// @Param: PIN248// @DisplayName: Second button Pin49// @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.50// @User: Standard51// @Values: -1:Disabled,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT652AP_GROUPINFO("PIN2", 2, AP_Button, pin[1], -1),5354// @Param: PIN355// @DisplayName: Third button Pin56// @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.57// @User: Standard58// @Values: -1:Disabled,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT659AP_GROUPINFO("PIN3", 3, AP_Button, pin[2], -1),6061// @Param: PIN462// @DisplayName: Fourth button Pin63// @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.64// @User: Standard65// @Values: -1:Disabled,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT666AP_GROUPINFO("PIN4", 4, AP_Button, pin[3], -1),6768// @Param: REPORT_SEND69// @DisplayName: Report send time70// @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.71// @User: Standard72// @Range: 0 360073AP_GROUPINFO("REPORT_SEND", 5, AP_Button, report_send_time, 10),7475// @Param: OPTIONS176// @DisplayName: Button Pin 1 Options77// @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.78// @User: Standard79// @Bitmask: 0:PWM Input,1:InvertInput80AP_GROUPINFO("OPTIONS1", 6, AP_Button, options[0], 0),8182// @Param: OPTIONS283// @DisplayName: Button Pin 2 Options84// @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.85// @User: Standard86// @Bitmask: 0:PWM Input,1:InvertInput87AP_GROUPINFO("OPTIONS2", 7, AP_Button, options[1], 0),8889// @Param: OPTIONS390// @DisplayName: Button Pin 3 Options91// @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.92// @Bitmask: 0:PWM Input,1:InvertInput93AP_GROUPINFO("OPTIONS3", 8, AP_Button, options[2], 0),9495// @Param: OPTIONS496// @DisplayName: Button Pin 4 Options97// @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.98// @User: Standard99// @Bitmask: 0:PWM Input,1:InvertInput100AP_GROUPINFO("OPTIONS4", 9, AP_Button, options[3], 0),101102// @Param: FUNC1103// @CopyFieldsFrom: RC1_OPTION104// @DisplayName: Button Pin 1 RC Channel function105// @Description: Auxiliary RC Options function executed on pin change106// @User: Standard107AP_GROUPINFO("FUNC1", 10, AP_Button, pin_func[0], (uint16_t)RC_Channel::AUX_FUNC::DO_NOTHING),108109// @Param: FUNC2110// @CopyFieldsFrom: BTN_FUNC1111// @DisplayName: Button Pin 2 RC Channel function112AP_GROUPINFO("FUNC2", 11, AP_Button, pin_func[1], (uint16_t)RC_Channel::AUX_FUNC::DO_NOTHING),113114// @Param: FUNC3115// @CopyFieldsFrom: BTN_FUNC1116// @DisplayName: Button Pin 3 RC Channel function117AP_GROUPINFO("FUNC3", 12, AP_Button, pin_func[2], (uint16_t)RC_Channel::AUX_FUNC::DO_NOTHING),118119// @Param: FUNC4120// @CopyFieldsFrom: BTN_FUNC1121// @DisplayName: Button Pin 4 RC Channel function122AP_GROUPINFO("FUNC4", 13, AP_Button, pin_func[3], (uint16_t)RC_Channel::AUX_FUNC::DO_NOTHING),123124AP_GROUPEND125};126127128// constructor129AP_Button::AP_Button(void)130{131AP_Param::setup_object_defaults(this, var_info);132133if (_singleton != nullptr) {134AP_HAL::panic("AP_Button must be singleton");135}136_singleton = this;137}138139/*140update and report, called from main loop141*/142void AP_Button::update(void)143{144if (!enable) {145return;146}147148// call setup pins at update rate (5Hz) to allow for runtime parameter change of pins149setup_pins();150151if (!initialised) {152initialised = true;153154// get initial mask155last_mask = get_mask();156debounce_mask = last_mask;157158// register 1kHz timer callback159hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&AP_Button::timer_update, void));160}161162// act on any changes in state163{164WITH_SEMAPHORE(last_debounced_change_ms_sem);165if (last_debounced_change_ms > last_debounce_ms) {166last_debounce_ms = last_debounced_change_ms;167}168}169170// update the PWM state:171uint8_t new_pwm_state = pwm_state;172for (uint8_t i=0; i<AP_BUTTON_NUM_PINS; i++) {173const uint8_t mask = (1U << i);174if (!is_pwm_input(i)) {175// not a PWM input176new_pwm_state &= ~mask;177continue;178}179const uint16_t pwm_us = pwm_pin_source[i].get_pwm_us();180if (pwm_us < RC_Channel::RC_MIN_LIMIT_PWM || pwm_us > RC_Channel::RC_MAX_LIMIT_PWM) {181// invalid pulse width, trigger low182if (pwm_state & mask) {183new_pwm_state &= ~mask;184}185continue;186}187// these values are the same as used in RC_Channel:188if (pwm_state & mask) {189// currently asserted; check to see if we should de-assert190if (pwm_us < RC_Channel::AUX_SWITCH_PWM_TRIGGER_LOW) {191new_pwm_state &= ~mask;192}193} else {194// currently not asserted; check to see if we should assert195if (pwm_us > RC_Channel::AUX_SWITCH_PWM_TRIGGER_HIGH) {196new_pwm_state |= mask;197}198}199}200const uint64_t now_ms = AP_HAL::millis64();201if (new_pwm_state != pwm_state) {202if (new_pwm_state != tentative_pwm_state) {203tentative_pwm_state = new_pwm_state;204pwm_start_debounce_ms = now_ms;205} else if (now_ms - pwm_start_debounce_ms > DEBOUNCE_MS) {206pwm_state = new_pwm_state;207last_debounce_ms = now_ms;208}209} else {210tentative_pwm_state = pwm_state;211pwm_start_debounce_ms = now_ms;212}213214#if HAL_GCS_ENABLED215if (last_debounce_ms != 0 &&216(AP_HAL::millis() - last_report_ms) > AP_BUTTON_REPORT_PERIOD_MS &&217(AP_HAL::millis64() - last_debounce_ms) < report_send_time*1000ULL) {218// send a change report219last_report_ms = AP_HAL::millis();220221// send a report to GCS222send_report();223}224#endif225226if (!aux_functions_initialised) {227run_aux_functions(true);228aux_functions_initialised = true;229}230231if (last_debounce_ms != 0 &&232last_debounce_ms != last_action_time_ms) {233last_action_time_ms = last_debounce_ms;234run_aux_functions(false);235}236}237238void AP_Button::run_aux_functions(bool force)239{240RC_Channel *rc_channel = rc().channel(1);241if (rc_channel == nullptr) {242return;243}244245for (uint8_t i=0; i<AP_BUTTON_NUM_PINS; i++) {246const RC_Channel::AUX_FUNC func = RC_Channel::AUX_FUNC(pin_func[i].get());247if (func == RC_Channel::AUX_FUNC::DO_NOTHING) {248continue;249}250const uint8_t value_mask = (1U<<i);251bool value;252if (is_pwm_input(i)) {253value = (pwm_state & value_mask) != 0;254} else {255value = (debounce_mask & value_mask) != 0;256}257if (is_input_inverted(i)) {258value = !value;259}260const bool actioned = ((state_actioned_mask & value_mask) != 0);261if (!force && value == actioned) {262// no change on this pin263continue;264}265// mark action as done:266if (value) {267state_actioned_mask |= value_mask;268} else {269state_actioned_mask &= ~value_mask;270}271272const RC_Channel::AuxSwitchPos pos = value ? RC_Channel::AuxSwitchPos::HIGH : RC_Channel::AuxSwitchPos::LOW;273// I wonder if we can do better here:274#if AP_RC_CHANNEL_AUX_FUNCTION_STRINGS_ENABLED275const char *str = rc_channel->string_for_aux_function(func);276if (str != nullptr) {277GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Button %i: executing (%s %s)", i+1, str, rc_channel->string_for_aux_pos(pos));278}279#endif280rc_channel->run_aux_function(func, pos, RC_Channel::AuxFuncTrigger::Source::BUTTON, i);281}282}283284// get state of a button285// used by scripting286bool AP_Button::get_button_state(uint8_t number)287{288// pins params are 1 indexed not zero289if (number == 0 || number > AP_BUTTON_NUM_PINS) {290return false;291}292293if (is_pwm_input(number-1)) {294return (pwm_state & (1U<<(number-1)));295}296297return ( ((1 << (number - 1)) & debounce_mask) != 0);298};299300/*301get current mask302*/303uint8_t AP_Button::get_mask(void)304{305uint8_t mask = 0;306for (uint8_t i=0; i<AP_BUTTON_NUM_PINS; i++) {307if (pin[i] == -1) {308continue;309}310if (is_pwm_input(i)) {311continue;312}313mask |= hal.gpio->read(pin[i]) << i;314}315316return mask;317}318319/*320called at 1kHz to check for button state change321*/322void AP_Button::timer_update(void)323{324if (!enable) {325return;326}327uint8_t mask = get_mask();328uint64_t now = AP_HAL::millis64();329if (mask != last_mask) {330last_mask = mask;331last_change_time_ms = now;332}333if (debounce_mask != last_mask &&334(now - last_change_time_ms) > DEBOUNCE_MS) {335// crude de-bouncing, debounces all buttons as one, not individually336debounce_mask = last_mask;337WITH_SEMAPHORE(last_debounced_change_ms_sem);338last_debounced_change_ms = now;339}340}341342#if HAL_GCS_ENABLED343/*344send a BUTTON_CHANGE report to the GCS345*/346void AP_Button::send_report(void) const347{348const uint8_t mask = last_mask | pwm_state;349const mavlink_button_change_t packet{350time_boot_ms: AP_HAL::millis(),351last_change_ms: uint32_t(last_debounce_ms),352state: mask,353};354gcs().send_to_active_channels(MAVLINK_MSG_ID_BUTTON_CHANGE,355(const char *)&packet);356}357#endif358359/*360setup the pins as input with pullup. We need pullup to give reliable361input with a pulldown button362*/363void AP_Button::setup_pins(void)364{365for (uint8_t i=0; i<AP_BUTTON_NUM_PINS; i++) {366if (is_pwm_input(i)) {367pwm_pin_source[i].set_pin(pin[i], "Button");368continue;369}370if (pin[i] == -1) {371continue;372}373374hal.gpio->pinMode(pin[i], HAL_GPIO_INPUT);375// setup pullup376hal.gpio->write(pin[i], 1);377}378}379380// check settings are valid381bool AP_Button::arming_checks(size_t buflen, char *buffer) const382{383if (!enable) {384return true;385}386for (uint8_t i=0; i<AP_BUTTON_NUM_PINS; i++) {387if (pin[i] != -1 && !hal.gpio->valid_pin(pin[i])) {388uint8_t servo_ch;389if (hal.gpio->pin_to_servo_channel(pin[i], servo_ch)) {390hal.util->snprintf(buffer, buflen, "BTN_PIN%u=%d, set SERVO%u_FUNCTION=-1", unsigned(i + 1), int(pin[i].get()), unsigned(servo_ch+1));391} else {392hal.util->snprintf(buffer, buflen, "BTN_PIN%u=%d invalid", unsigned(i + 1), int(pin[i].get()));393}394return false;395}396}397return true;398}399400namespace AP {401402AP_Button &button()403{404return *AP_Button::get_singleton();405}406407}408409#endif410411412