Fix unintended encoder doubleclick, Reduce long-press time
sdkconfig: - increase encoder dead-time to fix bug where encoder triggered multiple short pressed events at one press. E.g. instantly submitted value when entering a menu page sometimes button: - decrease input-timeout (long press time) to 500ms same as encoder long-press - empty encoder queue when changing to MENU - re-enable or increase joystick scaling to have more resolution at slower speeds
This commit is contained in:
parent
a5544adeb6
commit
c1d34237ee
@ -75,7 +75,10 @@ void buttonCommands::action (uint8_t count, bool lastPressLong){
|
||||
if (lastPressLong)
|
||||
{
|
||||
control->changeMode(controlMode_t::MENU);
|
||||
ESP_LOGW(TAG, "1x long press -> change to menu mode");
|
||||
ESP_LOGW(TAG, "1x long press -> clear encoder queue and change to menu mode");
|
||||
// clear encoder event queue (prevent menu from exiting immediately due to long press event just happend)
|
||||
rotary_encoder_event_t ev;
|
||||
while (xQueueReceive(encoderQueue, &ev, 0) == pdPASS);
|
||||
buzzer->beep(20, 20, 10);
|
||||
vTaskDelay(500 / portTICK_PERIOD_MS);
|
||||
}
|
||||
@ -156,7 +159,7 @@ void buttonCommands::action (uint8_t count, bool lastPressLong){
|
||||
// when not in MENU mode, repeatedly receives events from encoder button
|
||||
// and takes the corresponding action
|
||||
// this function has to be started once in a separate task
|
||||
#define INPUT_TIMEOUT 700 // duration of no button events, after which action is run (implicitly also is 'long-press' time)
|
||||
#define INPUT_TIMEOUT 500 // duration of no button events, after which action is run (implicitly also is 'long-press' time)
|
||||
void buttonCommands::startHandleLoop()
|
||||
{
|
||||
//-- variables --
|
||||
|
@ -254,7 +254,7 @@ joystickGenerateCommands_config_t joystickGenerateCommands_config{
|
||||
//-- maxDuty --
|
||||
// max duty when both motors are at equal ratio e.g. driving straight forward
|
||||
// better to be set less than 100% to have some reserve for boosting the outer tire when turning
|
||||
.maxDutyStraight = 85,
|
||||
.maxDutyStraight = 75,
|
||||
//-- maxBoost --
|
||||
// boost is amount of duty added to maxDutyStraight to outer tire while turning
|
||||
// => turning: inner tire gets slower, outer tire gets faster
|
||||
|
@ -148,7 +148,7 @@ void controlledArmchair::handle()
|
||||
stickDataLast = stickData;
|
||||
stickData = joystick_l->getData();
|
||||
// additionaly scale coordinates (more detail in slower area)
|
||||
joystick_scaleCoordinatesLinear(&stickData, 0.6, 0.5); // TODO: add scaling parameters to config
|
||||
joystick_scaleCoordinatesLinear(&stickData, 0.7, 0.45); // TODO: add scaling parameters to config
|
||||
// generate motor commands
|
||||
// only generate when the stick data actually changed (e.g. stick stayed in center)
|
||||
if (stickData.x != stickDataLast.x || stickData.y != stickDataLast.y)
|
||||
|
@ -1252,7 +1252,7 @@ CONFIG_WPA_MBEDTLS_CRYPTO=y
|
||||
#
|
||||
CONFIG_RE_MAX=1
|
||||
CONFIG_RE_INTERVAL_US=1000
|
||||
CONFIG_RE_BTN_DEAD_TIME_US=10000
|
||||
CONFIG_RE_BTN_DEAD_TIME_US=40000
|
||||
CONFIG_RE_BTN_PRESSED_LEVEL_0=y
|
||||
# CONFIG_RE_BTN_PRESSED_LEVEL_1 is not set
|
||||
CONFIG_RE_BTN_LONG_PRESS_TIME_US=500000
|
||||
|
@ -330,7 +330,7 @@ motorCommands_t joystick_generateCommandsDriving(joystickData_t data, joystickGe
|
||||
if (ratio > 1) ratio = 1; // >threshold -> 1
|
||||
|
||||
// -- calculate outer tire boost --
|
||||
#define BOOST_RATIO_MANIPULATION_SCALE 1.15 // >1 to apply boost slightly faster, this slightly compensates that available boost is most times less than reduction of inner duty, so for small turns the total speed feels more equal
|
||||
#define BOOST_RATIO_MANIPULATION_SCALE 1.05 // >1 to apply boost slightly faster, this slightly compensates that available boost is most times less than reduction of inner duty, so for small turns the total speed feels more equal
|
||||
float boostAmountOuter = data.radius*dutyBoost* ratio *BOOST_RATIO_MANIPULATION_SCALE;
|
||||
// limit to max amount
|
||||
if (boostAmountOuter > dutyBoost) boostAmountOuter = dutyBoost;
|
||||
|
Loading…
x
Reference in New Issue
Block a user