Add virtural keyboard for upDownInterrupter and RotaryEncoder.

This commit is contained in:
whywilson 2025-07-26 07:17:07 +08:00
parent 949d96a676
commit 00be809794
9 changed files with 183 additions and 67 deletions

View File

@ -33,7 +33,9 @@ int BuzzerFeedbackThread::handleInputEvent(const InputEvent *event)
break;
case INPUT_BROKER_UP:
case INPUT_BROKER_UP_LONG:
case INPUT_BROKER_DOWN:
case INPUT_BROKER_DOWN_LONG:
case INPUT_BROKER_LEFT:
case INPUT_BROKER_RIGHT:
playChirp(); // Navigation feedback

View File

@ -64,6 +64,9 @@ void VirtualKeyboard::initializeKeyboard()
void VirtualKeyboard::draw(OLEDDisplay *display, int16_t offsetX, int16_t offsetY)
{
// Clear the display to avoid overlapping with other UI elements
display->clear();
// Set initial color and font
display->setColor(WHITE);
display->setFont(FONT_SMALL);
@ -145,7 +148,7 @@ void VirtualKeyboard::drawInputArea(OLEDDisplay *display, int16_t offsetX, int16
}
// Handle text overflow with scrolling
int textPadding = 4;
int textPadding = 6; // 2px left padding + 4px right padding for cursor space
int maxWidth = boxWidth - textPadding;
int textWidth = display->getStringWidth(displayText.c_str());
@ -158,6 +161,13 @@ void VirtualKeyboard::drawInputArea(OLEDDisplay *display, int16_t offsetX, int16
}
if (scrolledText != displayText) {
scrolledText = "..." + scrolledText;
// Recalculate width with ellipsis and ensure it still fits
textWidth = display->getStringWidth(scrolledText.c_str());
while (textWidth > maxWidth && scrolledText.length() > 3) {
// Remove one character after "..." and recalculate
scrolledText = "..." + scrolledText.substr(4);
textWidth = display->getStringWidth(scrolledText.c_str());
}
}
}
@ -172,8 +182,9 @@ void VirtualKeyboard::drawInputArea(OLEDDisplay *display, int16_t offsetX, int16
// Draw cursor at the end of visible text - aligned with text baseline
if (!inputText.empty() || true) { // Always show cursor for visibility
int cursorX = textX + display->getStringWidth(scrolledText.c_str());
// Ensure cursor stays within box bounds
if (cursorX < offsetX + boxWidth - 2) {
// Ensure cursor stays within box bounds with proper margin from right edge
int rightBoundary = offsetX + 2 + boxWidth - 3; // 3px margin from right border
if (cursorX < rightBoundary) {
// Align cursor properly with the text baseline and height - moved down by 2 pixels
display->drawVerticalLine(cursorX, textY + 2, 10);
}
@ -277,7 +288,7 @@ char VirtualKeyboard::getCharForKey(const VirtualKey &key, bool isLongPress)
void VirtualKeyboard::moveCursorUp()
{
resetTimeout(); // Reset timeout on any input activity
resetTimeout();
// If we're on the close button, move to keyboard
if (cursorOnCloseButton) {
@ -322,7 +333,7 @@ void VirtualKeyboard::moveCursorUp()
void VirtualKeyboard::moveCursorDown()
{
resetTimeout(); // Reset timeout on any input activity
resetTimeout();
uint8_t originalRow = cursorRow;
if (cursorRow < KEYBOARD_ROWS - 1) {
@ -354,7 +365,7 @@ void VirtualKeyboard::moveCursorDown()
void VirtualKeyboard::moveCursorLeft()
{
resetTimeout(); // Reset timeout on any input activity
resetTimeout();
// Find the previous valid key position
do {
@ -375,7 +386,7 @@ void VirtualKeyboard::moveCursorLeft()
void VirtualKeyboard::moveCursorRight()
{
resetTimeout(); // Reset timeout on any input activity
resetTimeout();
// If we're on the close button, go back to keyboard
if (cursorOnCloseButton) {

View File

@ -7,10 +7,15 @@
#include "graphics/ScreenFonts.h"
#include "graphics/SharedUIDisplay.h"
#include "graphics/images.h"
#include "input/RotaryEncoderInterruptImpl1.h"
#include "input/UpDownInterruptImpl1.h"
#include "main.h"
#include <algorithm>
#include <string>
#include <vector>
#if HAS_TRACKBALL
#include "input/TrackballInterruptImpl1.h"
#endif
#ifdef ARCH_ESP32
#include "esp_task_wdt.h"
@ -125,6 +130,9 @@ void NotificationRenderer::drawBannercallback(OLEDDisplay *display, OLEDDisplayU
case notificationTypeEnum::number_picker:
drawNumberPicker(display, state);
break;
case notificationTypeEnum::text_input:
// text_input is handled at the top of the function
break;
}
}
@ -615,59 +623,64 @@ void NotificationRenderer::drawTextInput(OLEDDisplay *display, OLEDDisplayUiStat
return;
}
// Handle input events for virtual keyboard navigation
if (inEvent.inputEvent != INPUT_BROKER_NONE) {
if (inEvent.inputEvent == INPUT_BROKER_UP) {
virtualKeyboard->moveCursorUp();
// high frequency for move cursor left/right than up/down with encoders
extern ::RotaryEncoderInterruptImpl1 *rotaryEncoderInterruptImpl1;
extern ::UpDownInterruptImpl1 *upDownInterruptImpl1;
if (::rotaryEncoderInterruptImpl1 || ::upDownInterruptImpl1) {
virtualKeyboard->moveCursorLeft();
} else {
virtualKeyboard->moveCursorUp();
}
} else if (inEvent.inputEvent == INPUT_BROKER_DOWN) {
virtualKeyboard->moveCursorDown();
extern ::RotaryEncoderInterruptImpl1 *rotaryEncoderInterruptImpl1;
extern ::UpDownInterruptImpl1 *upDownInterruptImpl1;
if (::rotaryEncoderInterruptImpl1 || ::upDownInterruptImpl1) {
virtualKeyboard->moveCursorRight();
} else {
virtualKeyboard->moveCursorDown();
}
} else if (inEvent.inputEvent == INPUT_BROKER_LEFT) {
virtualKeyboard->moveCursorLeft();
} else if (inEvent.inputEvent == INPUT_BROKER_RIGHT) {
virtualKeyboard->moveCursorRight();
} else if (inEvent.inputEvent == INPUT_BROKER_UP_LONG) {
virtualKeyboard->moveCursorUp();
} else if (inEvent.inputEvent == INPUT_BROKER_DOWN_LONG) {
virtualKeyboard->moveCursorDown();
} else if (inEvent.inputEvent == INPUT_BROKER_ALT_PRESS) {
// Long press UP = move left
virtualKeyboard->moveCursorLeft();
} else if (inEvent.inputEvent == INPUT_BROKER_USER_PRESS) {
// Long press DOWN = move right
virtualKeyboard->moveCursorRight();
} else if (inEvent.inputEvent == INPUT_BROKER_SELECT) {
virtualKeyboard->handlePress();
} else if (inEvent.inputEvent == INPUT_BROKER_SELECT_LONG) {
virtualKeyboard->handleLongPress();
} else if (inEvent.inputEvent == INPUT_BROKER_CANCEL) {
// Cancel virtual keyboard - call callback with empty string
auto callback = textInputCallback; // Store callback before clearing
// Clean up first to prevent re-entry
auto callback = textInputCallback;
delete virtualKeyboard;
virtualKeyboard = nullptr;
textInputCallback = nullptr;
resetBanner();
// Call callback after cleanup
if (callback) {
callback("");
}
// Restore normal overlays
if (screen) {
screen->setFrames(graphics::Screen::FOCUS_PRESERVE);
}
return;
}
// Reset input event after processing
// Consume the event after processing for virtual keyboard
inEvent.inputEvent = INPUT_BROKER_NONE;
}
// Clear the display and draw virtual keyboard
display->setColor(BLACK);
display->fillRect(0, 0, display->getWidth(), display->getHeight());
display->setColor(WHITE);
// Draw the virtual keyboard - clear only when needed
virtualKeyboard->draw(display, 0, 0);
} else {
// If virtualKeyboard is null, reset the banner to avoid getting stuck
LOG_INFO("Virtual keyboard is null - resetting banner");
resetBanner();
}
}

View File

@ -4,13 +4,15 @@
enum input_broker_event {
INPUT_BROKER_NONE = 0,
INPUT_BROKER_SELECT = 10,
INPUT_BROKER_SELECT_LONG,
INPUT_BROKER_UP = 17,
INPUT_BROKER_DOWN = 18,
INPUT_BROKER_LEFT = 19,
INPUT_BROKER_RIGHT = 20,
INPUT_BROKER_CANCEL = 24,
INPUT_BROKER_BACK = 27,
INPUT_BROKER_SELECT_LONG = 28,
INPUT_BROKER_UP_LONG = 29,
INPUT_BROKER_DOWN_LONG = 30,
INPUT_BROKER_USER_PRESS,
INPUT_BROKER_ALT_PRESS,
INPUT_BROKER_ALT_LONG,

View File

@ -42,8 +42,8 @@ void TrackballInterruptBase::init(uint8_t pinDown, uint8_t pinUp, uint8_t pinLef
attachInterrupt(this->_pinRight, onIntRight, TB_DIRECTION);
}
LOG_DEBUG("Trackball GPIO initialized (%d, %d, %d, %d, %d)", this->_pinUp, this->_pinDown, this->_pinLeft, this->_pinRight,
pinPress);
LOG_DEBUG("Trackball GPIO initialized - UP:%d DOWN:%d LEFT:%d RIGHT:%d PRESS:%d", this->_pinUp, this->_pinDown,
this->_pinLeft, this->_pinRight, pinPress);
this->setInterval(100);
}
@ -65,9 +65,8 @@ int32_t TrackballInterruptBase::runOnce()
#endif
if (!buttonStillPressed) {
// Button released
// Button released - check if it was a short press
if (pressDuration < LONG_PRESS_DURATION) {
// Short press
e.inputEvent = this->_eventPressed;
}
// Reset state
@ -75,15 +74,10 @@ int32_t TrackballInterruptBase::runOnce()
pressStartTime = 0;
lastLongPressEventTime = 0;
this->action = TB_ACTION_NONE;
} else if (pressDuration >= LONG_PRESS_DURATION) {
// Long press detected
uint32_t currentTime = millis();
// Only trigger long press event if enough time has passed since the last one
if (lastLongPressEventTime == 0 || (currentTime - lastLongPressEventTime) >= LONG_PRESS_REPEAT_INTERVAL) {
e.inputEvent = this->_eventPressedLong;
lastLongPressEventTime = currentTime;
}
this->action = TB_ACTION_PRESSED_LONG;
} else if (pressDuration >= LONG_PRESS_DURATION && lastLongPressEventTime == 0) {
// First long press event only - avoid repeated events that cause lag
e.inputEvent = this->_eventPressedLong;
lastLongPressEventTime = millis();
}
}
@ -113,16 +107,12 @@ int32_t TrackballInterruptBase::runOnce()
pressStartTime = millis();
// Don't send event yet, wait to see if it's a long press
} else if (this->action == TB_ACTION_UP && !digitalRead(_pinUp)) {
// LOG_DEBUG("Trackball event UP");
e.inputEvent = this->_eventUp;
} else if (this->action == TB_ACTION_DOWN && !digitalRead(_pinDown)) {
// LOG_DEBUG("Trackball event DOWN");
e.inputEvent = this->_eventDown;
} else if (this->action == TB_ACTION_LEFT && !digitalRead(_pinLeft)) {
// LOG_DEBUG("Trackball event LEFT");
e.inputEvent = this->_eventLeft;
} else if (this->action == TB_ACTION_RIGHT && !digitalRead(_pinRight)) {
// LOG_DEBUG("Trackball event RIGHT");
e.inputEvent = this->_eventRight;
}
#endif

View File

@ -52,7 +52,7 @@ class TrackballInterruptBase : public Observable<const InputEvent *>, public con
bool pressDetected = false;
uint32_t lastLongPressEventTime = 0;
static const uint32_t LONG_PRESS_DURATION = 500; // ms
static const uint32_t LONG_PRESS_REPEAT_INTERVAL = 500; // ms - interval between repeated long press events
static const uint32_t LONG_PRESS_REPEAT_INTERVAL = 300; // ms - interval between repeated long press events
private:
input_broker_event _eventDown = INPUT_BROKER_NONE;

View File

@ -7,14 +7,19 @@ UpDownInterruptBase::UpDownInterruptBase(const char *name) : concurrency::OSThre
}
void UpDownInterruptBase::init(uint8_t pinDown, uint8_t pinUp, uint8_t pinPress, input_broker_event eventDown,
input_broker_event eventUp, input_broker_event eventPressed, void (*onIntDown)(),
input_broker_event eventUp, input_broker_event eventPressed, input_broker_event eventPressedLong,
input_broker_event eventUpLong, input_broker_event eventDownLong, void (*onIntDown)(),
void (*onIntUp)(), void (*onIntPress)(), unsigned long updownDebounceMs)
{
this->_pinDown = pinDown;
this->_pinUp = pinUp;
this->_pinPress = pinPress;
this->_eventDown = eventDown;
this->_eventUp = eventUp;
this->_eventPressed = eventPressed;
this->_eventPressedLong = eventPressedLong;
this->_eventUpLong = eventUpLong;
this->_eventDownLong = eventDownLong;
pinMode(pinPress, INPUT_PULLUP);
pinMode(this->_pinDown, INPUT_PULLUP);
@ -26,7 +31,7 @@ void UpDownInterruptBase::init(uint8_t pinDown, uint8_t pinUp, uint8_t pinPress,
LOG_DEBUG("Up/down/press GPIO initialized (%d, %d, %d)", this->_pinUp, this->_pinDown, pinPress);
this->setInterval(100);
this->setInterval(20);
}
int32_t UpDownInterruptBase::runOnce()
@ -34,23 +39,83 @@ int32_t UpDownInterruptBase::runOnce()
InputEvent e;
e.inputEvent = INPUT_BROKER_NONE;
unsigned long now = millis();
if (this->action == UPDOWN_ACTION_PRESSED) {
if (now - lastPressKeyTime >= pressDebounceMs) {
lastPressKeyTime = now;
LOG_DEBUG("GPIO event Press");
e.inputEvent = this->_eventPressed;
// Read all button states once at the beginning
bool pressButtonPressed = !digitalRead(_pinPress);
bool upButtonPressed = !digitalRead(_pinUp);
bool downButtonPressed = !digitalRead(_pinDown);
// Handle initial button press detection - only if not already detected
if (this->action == UPDOWN_ACTION_PRESSED && pressButtonPressed && !pressDetected) {
pressDetected = true;
pressStartTime = now;
} else if (this->action == UPDOWN_ACTION_UP && upButtonPressed && !upDetected) {
upDetected = true;
upStartTime = now;
} else if (this->action == UPDOWN_ACTION_DOWN && downButtonPressed && !downDetected) {
downDetected = true;
downStartTime = now;
}
// Handle long press detection for press button
if (pressDetected && pressStartTime > 0) {
uint32_t pressDuration = now - pressStartTime;
if (!pressButtonPressed) {
// Button released
if (pressDuration < LONG_PRESS_DURATION && now - lastPressKeyTime >= pressDebounceMs) {
lastPressKeyTime = now;
e.inputEvent = this->_eventPressed;
}
// Reset state
pressDetected = false;
pressStartTime = 0;
lastPressLongEventTime = 0;
} else if (pressDuration >= LONG_PRESS_DURATION && lastPressLongEventTime == 0) {
// First long press event only - avoid repeated events causing lag
e.inputEvent = this->_eventPressedLong;
lastPressLongEventTime = now;
}
} else if (this->action == UPDOWN_ACTION_UP) {
if (now - lastUpKeyTime >= updownDebounceMs) {
lastUpKeyTime = now;
LOG_DEBUG("GPIO event Up");
e.inputEvent = this->_eventUp;
}
// Handle long press detection for up button
if (upDetected && upStartTime > 0) {
uint32_t upDuration = now - upStartTime;
if (!upButtonPressed) {
// Button released
if (upDuration < LONG_PRESS_DURATION && now - lastUpKeyTime >= updownDebounceMs) {
lastUpKeyTime = now;
e.inputEvent = this->_eventUp;
}
// Reset state
upDetected = false;
upStartTime = 0;
lastUpLongEventTime = 0;
} else if (upDuration >= LONG_PRESS_DURATION && lastUpLongEventTime == 0) {
// First long press event only - avoid repeated events causing lag
e.inputEvent = this->_eventUpLong;
lastUpLongEventTime = now;
}
} else if (this->action == UPDOWN_ACTION_DOWN) {
if (now - lastDownKeyTime >= updownDebounceMs) {
lastDownKeyTime = now;
LOG_DEBUG("GPIO event Down");
e.inputEvent = this->_eventDown;
}
// Handle long press detection for down button
if (downDetected && downStartTime > 0) {
uint32_t downDuration = now - downStartTime;
if (!downButtonPressed) {
// Button released
if (downDuration < LONG_PRESS_DURATION && now - lastDownKeyTime >= updownDebounceMs) {
lastDownKeyTime = now;
e.inputEvent = this->_eventDown;
}
// Reset state
downDetected = false;
downStartTime = 0;
lastDownLongEventTime = 0;
} else if (downDuration >= LONG_PRESS_DURATION && lastDownLongEventTime == 0) {
e.inputEvent = this->_eventDownLong;
lastDownLongEventTime = now;
}
}
@ -60,8 +125,11 @@ int32_t UpDownInterruptBase::runOnce()
this->notifyObservers(&e);
}
this->action = UPDOWN_ACTION_NONE;
return 100;
if (!pressDetected && !upDetected && !downDetected) {
this->action = UPDOWN_ACTION_NONE;
}
return 20; // This will control how the input frequency
}
void UpDownInterruptBase::intPressHandler()

View File

@ -8,7 +8,8 @@ class UpDownInterruptBase : public Observable<const InputEvent *>, public concur
public:
explicit UpDownInterruptBase(const char *name);
void init(uint8_t pinDown, uint8_t pinUp, uint8_t pinPress, input_broker_event eventDown, input_broker_event eventUp,
input_broker_event eventPressed, void (*onIntDown)(), void (*onIntUp)(), void (*onIntPress)(),
input_broker_event eventPressed, input_broker_event eventPressedLong, input_broker_event eventUpLong,
input_broker_event eventDownLong, void (*onIntDown)(), void (*onIntUp)(), void (*onIntPress)(),
unsigned long updownDebounceMs = 50);
void intPressHandler();
void intDownHandler();
@ -17,16 +18,41 @@ class UpDownInterruptBase : public Observable<const InputEvent *>, public concur
int32_t runOnce() override;
protected:
enum UpDownInterruptBaseActionType { UPDOWN_ACTION_NONE, UPDOWN_ACTION_PRESSED, UPDOWN_ACTION_UP, UPDOWN_ACTION_DOWN };
enum UpDownInterruptBaseActionType {
UPDOWN_ACTION_NONE,
UPDOWN_ACTION_PRESSED,
UPDOWN_ACTION_PRESSED_LONG,
UPDOWN_ACTION_UP,
UPDOWN_ACTION_UP_LONG,
UPDOWN_ACTION_DOWN,
UPDOWN_ACTION_DOWN_LONG
};
volatile UpDownInterruptBaseActionType action = UPDOWN_ACTION_NONE;
// Long press detection variables
uint32_t pressStartTime = 0;
uint32_t upStartTime = 0;
uint32_t downStartTime = 0;
bool pressDetected = false;
bool upDetected = false;
bool downDetected = false;
uint32_t lastPressLongEventTime = 0;
uint32_t lastUpLongEventTime = 0;
uint32_t lastDownLongEventTime = 0;
static const uint32_t LONG_PRESS_DURATION = 300;
static const uint32_t LONG_PRESS_REPEAT_INTERVAL = 300;
private:
uint8_t _pinDown = 0;
uint8_t _pinUp = 0;
uint8_t _pinPress = 0;
input_broker_event _eventDown = INPUT_BROKER_NONE;
input_broker_event _eventUp = INPUT_BROKER_NONE;
input_broker_event _eventPressed = INPUT_BROKER_NONE;
input_broker_event _eventPressedLong = INPUT_BROKER_NONE;
input_broker_event _eventUpLong = INPUT_BROKER_NONE;
input_broker_event _eventDownLong = INPUT_BROKER_NONE;
const char *_originName;
unsigned long lastUpKeyTime = 0;

View File

@ -20,9 +20,13 @@ bool UpDownInterruptImpl1::init()
input_broker_event eventDown = INPUT_BROKER_DOWN;
input_broker_event eventUp = INPUT_BROKER_UP;
input_broker_event eventPressed = INPUT_BROKER_SELECT;
input_broker_event eventPressedLong = INPUT_BROKER_SELECT_LONG;
input_broker_event eventUpLong = INPUT_BROKER_UP_LONG;
input_broker_event eventDownLong = INPUT_BROKER_DOWN_LONG;
UpDownInterruptBase::init(pinDown, pinUp, pinPress, eventDown, eventUp, eventPressed, UpDownInterruptImpl1::handleIntDown,
UpDownInterruptImpl1::handleIntUp, UpDownInterruptImpl1::handleIntPressed);
UpDownInterruptBase::init(pinDown, pinUp, pinPress, eventDown, eventUp, eventPressed, eventPressedLong, eventUpLong,
eventDownLong, UpDownInterruptImpl1::handleIntDown, UpDownInterruptImpl1::handleIntUp,
UpDownInterruptImpl1::handleIntPressed);
inputBroker->registerSource(this);
return true;
}