|
|
|
@ -69,6 +69,34 @@ const AP_Param::GroupInfo AP_Button::var_info[] = {
@@ -69,6 +69,34 @@ const AP_Param::GroupInfo AP_Button::var_info[] = {
|
|
|
|
|
// @Range: 0 3600
|
|
|
|
|
AP_GROUPINFO("REPORT_SEND", 5, AP_Button, report_send_time, 10), |
|
|
|
|
|
|
|
|
|
// @Param: OPTIONS1
|
|
|
|
|
// @DisplayName: Button Pin 1 Options
|
|
|
|
|
// @Description: Options for Pin 1
|
|
|
|
|
// @User: Standard
|
|
|
|
|
// @Bitmask: 0:PWM Input,1:InvertInput
|
|
|
|
|
AP_GROUPINFO("OPTIONS1", 6, AP_Button, options[0], 0), |
|
|
|
|
|
|
|
|
|
// @Param: OPTIONS2
|
|
|
|
|
// @DisplayName: Button Pin 2 Options
|
|
|
|
|
// @Description: Options for Pin 2
|
|
|
|
|
// @User: Standard
|
|
|
|
|
// @Bitmask: 0:PWM Input,1:InvertInput
|
|
|
|
|
AP_GROUPINFO("OPTIONS2", 7, AP_Button, options[1], 0), |
|
|
|
|
|
|
|
|
|
// @Param: OPTIONS3
|
|
|
|
|
// @DisplayName: Button Pin 3 Options
|
|
|
|
|
// @Description: Options for Pin 3
|
|
|
|
|
// @User: Standard
|
|
|
|
|
// @Bitmask: 0:PWM Input,1:InvertInput
|
|
|
|
|
AP_GROUPINFO("OPTIONS3", 8, AP_Button, options[2], 0), |
|
|
|
|
|
|
|
|
|
// @Param: OPTIONS4
|
|
|
|
|
// @DisplayName: Button Pin 4 Options
|
|
|
|
|
// @Description: Options for Pin 4
|
|
|
|
|
// @User: Standard
|
|
|
|
|
// @Bitmask: 0:PWM Input,1:InvertInput
|
|
|
|
|
AP_GROUPINFO("OPTIONS4", 9, AP_Button, options[3], 0), |
|
|
|
|
|
|
|
|
|
AP_GROUPEND
|
|
|
|
|
}; |
|
|
|
|
|
|
|
|
@ -107,6 +135,31 @@ void AP_Button::update(void)
@@ -107,6 +135,31 @@ void AP_Button::update(void)
|
|
|
|
|
hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&AP_Button::timer_update, void));
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// act on any changes in state
|
|
|
|
|
{ |
|
|
|
|
WITH_SEMAPHORE(last_debounced_change_ms_sem); |
|
|
|
|
if (last_debounced_change_ms > last_debounce_ms) { |
|
|
|
|
last_debounce_ms = last_debounced_change_ms; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// update the PWM state:
|
|
|
|
|
uint8_t new_pwm_state = 0; |
|
|
|
|
for (uint8_t i=0; i<AP_BUTTON_NUM_PINS; i++) { |
|
|
|
|
if (!is_pwm_input(i)) { |
|
|
|
|
// not a PWM input
|
|
|
|
|
continue; |
|
|
|
|
} |
|
|
|
|
const uint16_t pwm_us = pwm_pin_source[i].get_pwm_us(); |
|
|
|
|
// these values are the same as used in RC_Channel:
|
|
|
|
|
new_pwm_state |= pwm_us > 1800 && pwm_us < 2200; |
|
|
|
|
} |
|
|
|
|
if (new_pwm_state != pwm_state) { |
|
|
|
|
pwm_state = new_pwm_state; |
|
|
|
|
last_debounced_change_ms = AP_HAL::millis64(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// act on any changes in state
|
|
|
|
|
if (last_change_time_ms != 0 && |
|
|
|
|
(AP_HAL::millis() - last_report_ms) > AP_BUTTON_REPORT_PERIOD_MS && |
|
|
|
|
(AP_HAL::millis64() - last_change_time_ms) < report_send_time*1000ULL) { |
|
|
|
@ -126,7 +179,11 @@ bool AP_Button::get_button_state(uint8_t number)
@@ -126,7 +179,11 @@ bool AP_Button::get_button_state(uint8_t number)
|
|
|
|
|
if (number == 0 || number > AP_BUTTON_NUM_PINS) { |
|
|
|
|
return false; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
if (is_pwm_input(number-1)) { |
|
|
|
|
return (pwm_state & (1U<<(number-1))); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
return ( ((1 << (number - 1)) & debounce_mask) != 0); |
|
|
|
|
}; |
|
|
|
|
|
|
|
|
@ -140,8 +197,12 @@ uint8_t AP_Button::get_mask(void)
@@ -140,8 +197,12 @@ uint8_t AP_Button::get_mask(void)
|
|
|
|
|
if (pin[i] == -1) { |
|
|
|
|
continue; |
|
|
|
|
} |
|
|
|
|
if (is_pwm_input(i)) { |
|
|
|
|
continue; |
|
|
|
|
} |
|
|
|
|
mask |= hal.gpio->read(pin[i]) << i; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
return mask; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -159,9 +220,11 @@ void AP_Button::timer_update(void)
@@ -159,9 +220,11 @@ void AP_Button::timer_update(void)
|
|
|
|
|
last_mask = mask; |
|
|
|
|
last_change_time_ms = now; |
|
|
|
|
} |
|
|
|
|
if ((now - last_change_time_ms) > DEBOUNCE_MS) { |
|
|
|
|
if (debounce_mask != last_mask && |
|
|
|
|
(now - last_change_time_ms) > DEBOUNCE_MS) { |
|
|
|
|
// crude de-bouncing, debounces all buttons as one, not individually
|
|
|
|
|
debounce_mask = last_mask; |
|
|
|
|
last_debounced_change_ms = now; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -170,10 +233,11 @@ void AP_Button::timer_update(void)
@@ -170,10 +233,11 @@ void AP_Button::timer_update(void)
|
|
|
|
|
*/ |
|
|
|
|
void AP_Button::send_report(void) |
|
|
|
|
{ |
|
|
|
|
const uint8_t mask = last_mask | pwm_state; |
|
|
|
|
const mavlink_button_change_t packet{ |
|
|
|
|
time_boot_ms: AP_HAL::millis(), |
|
|
|
|
last_change_ms: uint32_t(last_change_time_ms), |
|
|
|
|
state: last_mask |
|
|
|
|
last_change_ms: uint32_t(last_debounce_ms), |
|
|
|
|
state: mask, |
|
|
|
|
}; |
|
|
|
|
gcs().send_to_active_channels(MAVLINK_MSG_ID_BUTTON_CHANGE, |
|
|
|
|
(const char *)&packet); |
|
|
|
@ -186,9 +250,14 @@ void AP_Button::send_report(void)
@@ -186,9 +250,14 @@ void AP_Button::send_report(void)
|
|
|
|
|
void AP_Button::setup_pins(void) |
|
|
|
|
{ |
|
|
|
|
for (uint8_t i=0; i<AP_BUTTON_NUM_PINS; i++) { |
|
|
|
|
if (is_pwm_input(i)) { |
|
|
|
|
pwm_pin_source[i].set_pin(pin[i], "Button"); |
|
|
|
|
continue; |
|
|
|
|
} |
|
|
|
|
if (pin[i] == -1) { |
|
|
|
|
continue; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
hal.gpio->pinMode(pin[i], HAL_GPIO_INPUT); |
|
|
|
|
// setup pullup
|
|
|
|
|
hal.gpio->write(pin[i], 1); |
|
|
|
|