Files
firmware/src/input/RotaryEncoderInterruptBase.cpp

148 lines
5.0 KiB
C++
Raw Normal View History

2022-01-08 13:13:29 +01:00
#include "RotaryEncoderInterruptBase.h"
2022-05-07 20:31:21 +10:00
#include "configuration.h"
2022-01-08 13:13:29 +01:00
2026-01-03 21:19:24 +01:00
RotaryEncoderInterruptBase::RotaryEncoderInterruptBase(const char *name) : concurrency::OSThread(name) { this->_originName = name; }
2022-01-11 13:12:04 +01:00
void RotaryEncoderInterruptBase::init(
2026-01-03 21:19:24 +01:00
uint8_t pinA, uint8_t pinB, uint8_t pinPress, input_broker_event eventCw, input_broker_event eventCcw, input_broker_event eventPressed,
input_broker_event eventPressedLong,
2022-05-07 20:31:21 +10:00
// std::function<void(void)> onIntA, std::function<void(void)> onIntB, std::function<void(void)> onIntPress) :
2026-01-03 21:19:24 +01:00
void (*onIntA)(), void (*onIntB)(), void (*onIntPress)()) {
this->_pinA = pinA;
this->_pinB = pinB;
this->_pinPress = pinPress;
this->_eventCw = eventCw;
this->_eventCcw = eventCcw;
this->_eventPressed = eventPressed;
this->_eventPressedLong = eventPressedLong;
bool isRAK = false;
#ifdef RAK_4631
2026-01-03 21:19:24 +01:00
isRAK = true;
#endif
2026-01-03 21:19:24 +01:00
if (!isRAK || pinPress != 0) {
pinMode(pinPress, INPUT_PULLUP);
attachInterrupt(pinPress, onIntPress, CHANGE);
}
if (!isRAK || this->_pinA != 0) {
pinMode(this->_pinA, INPUT_PULLUP);
attachInterrupt(this->_pinA, onIntA, CHANGE);
}
if (!isRAK || this->_pinA != 0) {
pinMode(this->_pinB, INPUT_PULLUP);
attachInterrupt(this->_pinB, onIntB, CHANGE);
}
this->rotaryLevelA = digitalRead(this->_pinA);
this->rotaryLevelB = digitalRead(this->_pinB);
LOG_INFO("Rotary initialized (%d, %d, %d)", this->_pinA, this->_pinB, pinPress);
2022-01-08 13:13:29 +01:00
}
2026-01-03 21:19:24 +01:00
int32_t RotaryEncoderInterruptBase::runOnce() {
InputEvent e = {};
e.inputEvent = INPUT_BROKER_NONE;
e.source = this->_originName;
unsigned long now = millis();
// Handle press long/short detection
if (this->action == ROTARY_ACTION_PRESSED) {
bool buttonPressed = !digitalRead(_pinPress);
if (!pressDetected && buttonPressed) {
pressDetected = true;
pressStartTime = now;
2022-01-11 16:02:55 +01:00
}
2026-01-03 21:19:24 +01:00
if (pressDetected) {
uint32_t duration = now - pressStartTime;
if (!buttonPressed) {
// released -> if short press, send short, else already sent long
if (duration < LONG_PRESS_DURATION && now - lastPressKeyTime >= pressDebounceMs) {
lastPressKeyTime = now;
LOG_DEBUG("Rotary event Press short");
e.inputEvent = this->_eventPressed;
}
pressDetected = false;
pressStartTime = 0;
lastPressLongEventTime = 0;
this->action = ROTARY_ACTION_NONE;
2026-01-03 21:19:24 +01:00
} else if (duration >= LONG_PRESS_DURATION && this->_eventPressedLong != INPUT_BROKER_NONE && lastPressLongEventTime == 0) {
// fire single-shot long press
lastPressLongEventTime = now;
LOG_DEBUG("Rotary event Press long");
e.inputEvent = this->_eventPressedLong;
}
}
2026-01-03 21:19:24 +01:00
} else if (this->action == ROTARY_ACTION_CW) {
LOG_DEBUG("Rotary event CW");
e.inputEvent = this->_eventCw;
} else if (this->action == ROTARY_ACTION_CCW) {
LOG_DEBUG("Rotary event CCW");
e.inputEvent = this->_eventCcw;
}
if (e.inputEvent != INPUT_BROKER_NONE) {
this->notifyObservers(&e);
}
if (!pressDetected) {
this->action = ROTARY_ACTION_NONE;
}
return INT32_MAX;
2022-01-08 13:13:29 +01:00
}
2026-01-03 21:19:24 +01:00
void RotaryEncoderInterruptBase::intPressHandler() {
this->action = ROTARY_ACTION_PRESSED;
setIntervalFromNow(20); // start checking for long/short
2022-01-08 13:13:29 +01:00
}
2026-01-03 21:19:24 +01:00
void RotaryEncoderInterruptBase::intAHandler() {
// CW rotation (at least on most common rotary encoders)
int currentLevelA = digitalRead(this->_pinA);
if (this->rotaryLevelA == currentLevelA) {
return;
}
this->rotaryLevelA = currentLevelA;
this->rotaryStateCCW = intHandler(currentLevelA == HIGH, this->rotaryLevelB, ROTARY_ACTION_CCW, this->rotaryStateCCW);
2022-01-08 13:13:29 +01:00
}
2026-01-03 21:19:24 +01:00
void RotaryEncoderInterruptBase::intBHandler() {
// CW rotation (at least on most common rotary encoders)
int currentLevelB = digitalRead(this->_pinB);
if (this->rotaryLevelB == currentLevelB) {
return;
}
this->rotaryLevelB = currentLevelB;
this->rotaryStateCW = intHandler(currentLevelB == HIGH, this->rotaryLevelA, ROTARY_ACTION_CW, this->rotaryStateCW);
2022-01-12 22:50:37 +01:00
}
/**
* @brief Rotary action implementation.
* We assume, the following pin setup:
* A --||
2022-05-07 20:31:21 +10:00
* GND --||]========
2022-01-12 22:50:37 +01:00
* B --||
2022-05-07 20:31:21 +10:00
*
2022-01-12 22:50:37 +01:00
* @return The new state for rotary pin.
*/
2022-05-07 20:31:21 +10:00
RotaryEncoderInterruptBaseStateType RotaryEncoderInterruptBase::intHandler(bool actualPinRaising, int otherPinLevel,
RotaryEncoderInterruptBaseActionType action,
2026-01-03 21:19:24 +01:00
RotaryEncoderInterruptBaseStateType state) {
RotaryEncoderInterruptBaseStateType newState = state;
if (actualPinRaising && (otherPinLevel == LOW)) {
if (state == ROTARY_EVENT_CLEARED) {
newState = ROTARY_EVENT_OCCURRED;
if ((this->action != ROTARY_ACTION_PRESSED) && (this->action != action)) {
this->action = action;
}
2022-01-08 13:13:29 +01:00
}
2026-01-03 21:19:24 +01:00
} else if (!actualPinRaising && (otherPinLevel == HIGH)) {
// Logic to prevent bouncing.
newState = ROTARY_EVENT_CLEARED;
}
setIntervalFromNow(ROTARY_DELAY); // TODO: this modifies a non-volatile variable!
2022-01-12 22:50:37 +01:00
2026-01-03 21:19:24 +01:00
return newState;
2022-01-08 13:13:29 +01:00
}