mirror of https://github.com/ArduPilot/ardupilot
AP_Button: add debounce on PWM input
Co-authored-by: jmachuca77 <jaime@element.aero>
This commit is contained in:
parent
e0d03ce565
commit
f465a9336e
|
@ -201,9 +201,18 @@ void AP_Button::update(void)
|
|||
}
|
||||
}
|
||||
}
|
||||
const uint64_t now_ms = AP_HAL::millis64();
|
||||
if (new_pwm_state != pwm_state) {
|
||||
pwm_state = new_pwm_state;
|
||||
last_debounce_ms = AP_HAL::millis64();
|
||||
if (new_pwm_state != tentative_pwm_state) {
|
||||
tentative_pwm_state = new_pwm_state;
|
||||
pwm_start_debounce_ms = now_ms;
|
||||
} else if (now_ms - pwm_start_debounce_ms > DEBOUNCE_MS) {
|
||||
pwm_state = new_pwm_state;
|
||||
last_debounce_ms = now_ms;
|
||||
}
|
||||
} else {
|
||||
tentative_pwm_state = pwm_state;
|
||||
pwm_start_debounce_ms = now_ms;
|
||||
}
|
||||
|
||||
if (last_debounce_ms != 0 &&
|
||||
|
|
|
@ -76,6 +76,8 @@ private:
|
|||
|
||||
// current state of PWM pins:
|
||||
uint8_t pwm_state;
|
||||
uint8_t tentative_pwm_state; // for debouncing
|
||||
uint64_t pwm_start_debounce_ms;
|
||||
|
||||
// mask indicating which action was most recent taken for pins
|
||||
uint8_t state_actioned_mask;
|
||||
|
|
Loading…
Reference in New Issue