Path: blob/master/libraries/AP_Button/AP_Button.cpp
9446 views
/*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:AUXOUT645// @Range: -1 12746AP_GROUPINFO("PIN1", 1, AP_Button, pin[0], -1),4748// @Param: PIN249// @DisplayName: Second button Pin50// @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: Standard52// @Values: -1:Disabled,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT653// @Range: -1 12754AP_GROUPINFO("PIN2", 2, AP_Button, pin[1], -1),5556// @Param: PIN357// @DisplayName: Third button Pin58// @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.59// @User: Standard60// @Values: -1:Disabled,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT661// @Range: -1 12762AP_GROUPINFO("PIN3", 3, AP_Button, pin[2], -1),6364// @Param: PIN465// @DisplayName: Fourth button Pin66// @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.67// @User: Standard68// @Values: -1:Disabled,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT669// @Range: -1 12770AP_GROUPINFO("PIN4", 4, AP_Button, pin[3], -1),7172// @Param: REPORT_SEND73// @DisplayName: Report send time74// @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.75// @User: Standard76// @Range: 0 360077AP_GROUPINFO("REPORT_SEND", 5, AP_Button, report_send_time, 10),7879// @Param: OPTIONS180// @DisplayName: Button Pin 1 Options81// @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.82// @User: Standard83// @Bitmask: 0:PWM Input,1:InvertInput84AP_GROUPINFO("OPTIONS1", 6, AP_Button, options[0], 0),8586// @Param: OPTIONS287// @DisplayName: Button Pin 2 Options88// @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.89// @User: Standard90// @Bitmask: 0:PWM Input,1:InvertInput91AP_GROUPINFO("OPTIONS2", 7, AP_Button, options[1], 0),9293// @Param: OPTIONS394// @DisplayName: Button Pin 3 Options95// @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.96// @Bitmask: 0:PWM Input,1:InvertInput97AP_GROUPINFO("OPTIONS3", 8, AP_Button, options[2], 0),9899// @Param: OPTIONS4100// @DisplayName: Button Pin 4 Options101// @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.102// @User: Standard103// @Bitmask: 0:PWM Input,1:InvertInput104AP_GROUPINFO("OPTIONS4", 9, AP_Button, options[3], 0),105106// @Param: FUNC1107// @CopyFieldsFrom: RC1_OPTION108// @DisplayName: Button Pin 1 RC Channel function109// @Description: Auxiliary RC Options function executed on pin change110// @User: Standard111AP_GROUPINFO("FUNC1", 10, AP_Button, pin_func[0], (uint16_t)RC_Channel::AUX_FUNC::DO_NOTHING),112113// @Param: FUNC2114// @CopyFieldsFrom: BTN_FUNC1115// @DisplayName: Button Pin 2 RC Channel function116AP_GROUPINFO("FUNC2", 11, AP_Button, pin_func[1], (uint16_t)RC_Channel::AUX_FUNC::DO_NOTHING),117118// @Param: FUNC3119// @CopyFieldsFrom: BTN_FUNC1120// @DisplayName: Button Pin 3 RC Channel function121AP_GROUPINFO("FUNC3", 12, AP_Button, pin_func[2], (uint16_t)RC_Channel::AUX_FUNC::DO_NOTHING),122123// @Param: FUNC4124// @CopyFieldsFrom: BTN_FUNC1125// @DisplayName: Button Pin 4 RC Channel function126AP_GROUPINFO("FUNC4", 13, AP_Button, pin_func[3], (uint16_t)RC_Channel::AUX_FUNC::DO_NOTHING),127128AP_GROUPEND129};130131132// constructor133AP_Button::AP_Button(void)134{135AP_Param::setup_object_defaults(this, var_info);136137if (_singleton != nullptr) {138AP_HAL::panic("AP_Button must be singleton");139}140_singleton = this;141}142143/*144update and report, called from main loop145*/146void AP_Button::update(void)147{148if (!enable) {149return;150}151152// call setup pins at update rate (5Hz) to allow for runtime parameter change of pins153setup_pins();154155if (!initialised) {156initialised = true;157158// get initial mask159last_mask = get_mask();160debounce_mask = last_mask;161162// register 1kHz timer callback163hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&AP_Button::timer_update, void));164}165166// act on any changes in state167{168WITH_SEMAPHORE(last_debounced_change_ms_sem);169if (last_debounced_change_ms > last_debounce_ms) {170last_debounce_ms = last_debounced_change_ms;171}172}173174// update the PWM state:175uint8_t new_pwm_state = pwm_state;176for (uint8_t i=0; i<AP_BUTTON_NUM_PINS; i++) {177const uint8_t mask = (1U << i);178if (!is_pwm_input(i)) {179// not a PWM input180new_pwm_state &= ~mask;181continue;182}183const uint16_t pwm_us = pwm_pin_source[i].get_pwm_us();184if (pwm_us < RC_Channel::RC_MIN_LIMIT_PWM || pwm_us > RC_Channel::RC_MAX_LIMIT_PWM) {185// invalid pulse width, trigger low186if (pwm_state & mask) {187new_pwm_state &= ~mask;188}189continue;190}191// these values are the same as used in RC_Channel:192if (pwm_state & mask) {193// currently asserted; check to see if we should de-assert194if (pwm_us < RC_Channel::AUX_SWITCH_PWM_TRIGGER_LOW) {195new_pwm_state &= ~mask;196}197} else {198// currently not asserted; check to see if we should assert199if (pwm_us > RC_Channel::AUX_SWITCH_PWM_TRIGGER_HIGH) {200new_pwm_state |= mask;201}202}203}204const uint64_t now_ms = AP_HAL::millis64();205if (new_pwm_state != pwm_state) {206if (new_pwm_state != tentative_pwm_state) {207tentative_pwm_state = new_pwm_state;208pwm_start_debounce_ms = now_ms;209} else if (now_ms - pwm_start_debounce_ms > DEBOUNCE_MS) {210pwm_state = new_pwm_state;211last_debounce_ms = now_ms;212}213} else {214tentative_pwm_state = pwm_state;215pwm_start_debounce_ms = now_ms;216}217218#if HAL_GCS_ENABLED219if (last_debounce_ms != 0 &&220(AP_HAL::millis() - last_report_ms) > AP_BUTTON_REPORT_PERIOD_MS &&221(AP_HAL::millis64() - last_debounce_ms) < report_send_time*1000ULL) {222// send a change report223last_report_ms = AP_HAL::millis();224225// send a report to GCS226send_report();227}228#endif229230if (!aux_functions_initialised) {231run_aux_functions(true);232aux_functions_initialised = true;233}234235if (last_debounce_ms != 0 &&236last_debounce_ms != last_action_time_ms) {237last_action_time_ms = last_debounce_ms;238run_aux_functions(false);239}240}241242void AP_Button::run_aux_functions(bool force)243{244RC_Channel *rc_channel = rc().channel(1);245if (rc_channel == nullptr) {246return;247}248249for (uint8_t i=0; i<AP_BUTTON_NUM_PINS; i++) {250const RC_Channel::AUX_FUNC func = RC_Channel::AUX_FUNC(pin_func[i].get());251if (func == RC_Channel::AUX_FUNC::DO_NOTHING) {252continue;253}254const uint8_t value_mask = (1U<<i);255bool value;256if (is_pwm_input(i)) {257value = (pwm_state & value_mask) != 0;258} else {259value = (debounce_mask & value_mask) != 0;260}261if (is_input_inverted(i)) {262value = !value;263}264const bool actioned = ((state_actioned_mask & value_mask) != 0);265if (!force && value == actioned) {266// no change on this pin267continue;268}269// mark action as done:270if (value) {271state_actioned_mask |= value_mask;272} else {273state_actioned_mask &= ~value_mask;274}275276const RC_Channel::AuxSwitchPos pos = value ? RC_Channel::AuxSwitchPos::HIGH : RC_Channel::AuxSwitchPos::LOW;277// I wonder if we can do better here:278#if AP_RC_CHANNEL_AUX_FUNCTION_STRINGS_ENABLED279const char *str = rc_channel->string_for_aux_function(func);280if (str != nullptr) {281GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Button %i: executing (%s %s)", i+1, str, rc_channel->string_for_aux_pos(pos));282}283#endif284rc_channel->run_aux_function(func, pos, RC_Channel::AuxFuncTrigger::Source::BUTTON, i);285}286}287288// get state of a button289// used by scripting290bool AP_Button::get_button_state(uint8_t number)291{292// pins params are 1 indexed not zero293if (number == 0 || number > AP_BUTTON_NUM_PINS) {294return false;295}296297if (is_pwm_input(number-1)) {298return (pwm_state & (1U<<(number-1)));299}300301return ( ((1 << (number - 1)) & debounce_mask) != 0);302};303304/*305get current mask306*/307uint8_t AP_Button::get_mask(void)308{309uint8_t mask = 0;310for (uint8_t i=0; i<AP_BUTTON_NUM_PINS; i++) {311if (pin[i] == -1) {312continue;313}314if (is_pwm_input(i)) {315continue;316}317mask |= hal.gpio->read(pin[i]) << i;318}319320return mask;321}322323/*324called at 1kHz to check for button state change325*/326void AP_Button::timer_update(void)327{328if (!enable) {329return;330}331uint8_t mask = get_mask();332uint64_t now = AP_HAL::millis64();333if (mask != last_mask) {334last_mask = mask;335last_change_time_ms = now;336}337if (debounce_mask != last_mask &&338(now - last_change_time_ms) > DEBOUNCE_MS) {339// crude de-bouncing, debounces all buttons as one, not individually340debounce_mask = last_mask;341WITH_SEMAPHORE(last_debounced_change_ms_sem);342last_debounced_change_ms = now;343}344}345346#if HAL_GCS_ENABLED347/*348send a BUTTON_CHANGE report to the GCS349*/350void AP_Button::send_report(void) const351{352const uint8_t mask = last_mask | pwm_state;353const mavlink_button_change_t packet{354time_boot_ms: AP_HAL::millis(),355last_change_ms: uint32_t(last_debounce_ms),356state: mask,357};358gcs().send_to_active_channels(MAVLINK_MSG_ID_BUTTON_CHANGE,359(const char *)&packet);360}361#endif362363/*364setup the pins as input with pullup. We need pullup to give reliable365input with a pulldown button366*/367void AP_Button::setup_pins(void)368{369for (uint8_t i=0; i<AP_BUTTON_NUM_PINS; i++) {370if (is_pwm_input(i)) {371pwm_pin_source[i].set_pin(pin[i], "Button");372continue;373}374if (pin[i] == -1) {375continue;376}377378hal.gpio->pinMode(pin[i], HAL_GPIO_INPUT);379// setup pullup380hal.gpio->write(pin[i], 1);381}382}383384// check settings are valid385bool AP_Button::arming_checks(size_t buflen, char *buffer) const386{387if (!enable) {388return true;389}390for (uint8_t i=0; i<AP_BUTTON_NUM_PINS; i++) {391if (pin[i] != -1 && !hal.gpio->valid_pin(pin[i])) {392uint8_t servo_ch;393if (hal.gpio->pin_to_servo_channel(pin[i], servo_ch)) {394hal.util->snprintf(buffer, buflen, "BTN_PIN%u=%d, set SERVO%u_FUNCTION=-1", unsigned(i + 1), int(pin[i].get()), unsigned(servo_ch+1));395} else {396hal.util->snprintf(buffer, buflen, "BTN_PIN%u=%d invalid", unsigned(i + 1), int(pin[i].get()));397}398return false;399}400}401return true;402}403404namespace AP {405406AP_Button &button()407{408return *AP_Button::get_singleton();409}410411}412413#endif414415416