diff --git a/board_control/main/CMakeLists.txt b/board_control/main/CMakeLists.txt index 575bfc2..3ed4d7e 100644 --- a/board_control/main/CMakeLists.txt +++ b/board_control/main/CMakeLists.txt @@ -6,6 +6,7 @@ idf_component_register( "button.cpp" "auto.cpp" "uart.cpp" + "encoder.cpp" INCLUDE_DIRS "." ) diff --git a/board_control/main/encoder.cpp b/board_control/main/encoder.cpp new file mode 100644 index 0000000..887335a --- /dev/null +++ b/board_control/main/encoder.cpp @@ -0,0 +1,81 @@ + #include "encoder.h" +extern "C" +{ +#include +#include +#include +#include "freertos/FreeRTOS.h" +#include "freertos/task.h" +#include "driver/gpio.h" +#include "esp_log.h" +} + +#include "encoder.hpp" + +//------------------------- +//------- variables ------- +//------------------------- +static const char * TAG = "encoder"; +uint16_t encoderCount; +rotary_encoder_btn_state_t encoderButtonState = {}; +QueueHandle_t encoderQueue = NULL; + +//encoder config +rotary_encoder_t encoderConfig = { + .pin_a = PIN_A, + .pin_b = PIN_B, + .pin_btn = PIN_BUTTON, + .code = 1, + .store = encoderCount, + .index = 0, + .btn_pressed_time_us = 20000, + .btn_state = encoderButtonState +}; + + + +//================================== +//========== encoder_init ========== +//================================== +//initialize encoder +void encoder_init(){ + encoderQueue = xQueueCreate(QUEUE_SIZE, sizeof(rotary_encoder_event_t)); + rotary_encoder_init(encoderQueue); + rotary_encoder_add(&encoderConfig); +} + + + +//================================== +//========== task_encoder ========== +//================================== +//receive and handle encoder events +void task_encoder(void *arg) { + rotary_encoder_event_t ev; //store event data + while (1) { + if (xQueueReceive(encoderQueue, &ev, portMAX_DELAY)) { + //log enocder events + switch (ev.type){ + case RE_ET_CHANGED: + ESP_LOGI(TAG, "Event type: RE_ET_CHANGED, diff: %d", ev.diff); + break; + case RE_ET_BTN_PRESSED: + ESP_LOGI(TAG, "Button pressed"); + break; + case RE_ET_BTN_RELEASED: + ESP_LOGI(TAG, "Button released"); + break; + case RE_ET_BTN_CLICKED: + ESP_LOGI(TAG, "Button clicked"); + break; + case RE_ET_BTN_LONG_PRESSED: + ESP_LOGI(TAG, "Button long-pressed"); + break; + default: + ESP_LOGW(TAG, "Unknown event type"); + break; + } + } + } +} + diff --git a/board_control/main/encoder.hpp b/board_control/main/encoder.hpp new file mode 100644 index 0000000..18881ed --- /dev/null +++ b/board_control/main/encoder.hpp @@ -0,0 +1,18 @@ +extern "C" { +#include "freertos/FreeRTOS.h" // FreeRTOS related headers +#include "freertos/task.h" +#include "encoder.h" +} + +//config +#define QUEUE_SIZE 10 +#define PIN_A GPIO_NUM_25 +#define PIN_B GPIO_NUM_26 +#define PIN_BUTTON GPIO_NUM_27 + + +//init encoder with config in encoder.cpp +void encoder_init(); + +//task that handles encoder events +void task_encoder(void *arg); diff --git a/board_control/main/main.cpp b/board_control/main/main.cpp index 260310a..5537cf9 100644 --- a/board_control/main/main.cpp +++ b/board_control/main/main.cpp @@ -18,6 +18,7 @@ extern "C" #include "uart.hpp" +#include "encoder.hpp" //========================= @@ -28,6 +29,13 @@ extern "C" //#define UART_TEST_ONLY +//========================= +//====== encoder TEST ===== +//========================= +//only start encoder task +#define ENCODER_TEST_ONLY + + //tag for logging static const char * TAG = "main"; @@ -157,7 +165,7 @@ void setLoglevels(void){ //=========== app_main ============ //================================= extern "C" void app_main(void) { -#ifndef UART_TEST_ONLY +#if !defined(ENCODER_TEST_ONLY) && !defined(UART_TEST_ONLY) //enable 5V volate regulator gpio_pad_select_gpio(GPIO_NUM_17); gpio_set_direction(GPIO_NUM_17, GPIO_MODE_OUTPUT); @@ -214,24 +222,35 @@ extern "C" void app_main(void) { // vTaskDelay(2000 / portTICK_PERIOD_MS); // ESP_LOGI(TAG, "initializing http server"); // http_init_server(); - - #endif + //------------------------------------------- //--- create tasks for uart communication --- //------------------------------------------- - +#ifndef ENCODER_TEST_ONLY uart_init(); xTaskCreate(task_uartReceive, "task_uartReceive", 4096, NULL, 10, NULL); xTaskCreate(task_uartSend, "task_uartSend", 4096, NULL, 10, NULL); +#endif + + + //-------------------------------------------- + //----- create task that handles encoder ----- + //-------------------------------------------- +#ifndef UART_TEST_ONLY + encoder_init(); + xTaskCreate(task_encoder, "task_encoder", 4096, NULL, 10, NULL); +#endif + + //--- main loop --- //does nothing except for testing things //--- testing force http mode after startup --- vTaskDelay(5000 / portTICK_PERIOD_MS); - control.changeMode(controlMode_t::HTTP); + //control.changeMode(controlMode_t::HTTP); while(1){ vTaskDelay(1000 / portTICK_PERIOD_MS); //--------------------------------- diff --git a/board_single/main/CMakeLists.txt b/board_single/main/CMakeLists.txt index d0ac056..cbbf984 100644 --- a/board_single/main/CMakeLists.txt +++ b/board_single/main/CMakeLists.txt @@ -7,6 +7,8 @@ idf_component_register( "fan.cpp" "auto.cpp" "display.cpp" + "menu.cpp" + "encoder.cpp" INCLUDE_DIRS "." ) diff --git a/board_single/main/button.cpp b/board_single/main/button.cpp index 0efb449..06f4c9e 100644 --- a/board_single/main/button.cpp +++ b/board_single/main/button.cpp @@ -8,6 +8,7 @@ extern "C" } #include "button.hpp" +#include "encoder.hpp" @@ -37,46 +38,53 @@ buttonCommands::buttonCommands(gpio_evaluatedSwitch * button_f, evaluatedJoystic //---------------------------- //function that runs commands depending on a count value void buttonCommands::action (uint8_t count, bool lastPressLong){ - //--- variable declarations --- + //--- variables --- bool decelEnabled; //for different beeping when toggling commandSimple_t cmds[8]; //array for commands for automatedArmchair //--- get joystick position --- + //in case joystick is used for additional cases: //joystickData_t stickData = joystick->getData(); - //--- actions based on count --- - switch (count){ - //no such command - default: - ESP_LOGE(TAG, "no command for count=%d defined", count); - buzzer->beep(3, 400, 100); - break; + //--- run actions based on count --- + switch (count) + { + // ## no command ## + default: + ESP_LOGE(TAG, "no command for count=%d and long=%d defined", count, lastPressLong); + buzzer->beep(3, 400, 100); + break; - case 1: - //restart contoller when 1x long pressed - if (lastPressLong){ - ESP_LOGW(TAG, "RESTART"); - buzzer->beep(1,1000,1); - vTaskDelay(500 / portTICK_PERIOD_MS); - //esp_restart(); - //-> define joystick center or toggle freeze input (executed in control task) - control->sendButtonEvent(count); //TODO: always send button event to control task (not just at count=1) -> control.cpp has to be changed - return; - } - //note: disabled joystick calibration due to accidential trigger -// -// ESP_LOGW(TAG, "cmd %d: sending button event to control task", count); -// //-> define joystick center or toggle freeze input (executed in control task) -// control->sendButtonEvent(count); //TODO: always send button event to control task (not just at count=1) -> control.cpp has to be changed - break; - case 2: - //run automatic commands to lift leg support when pressed 1x short 1x long - if (lastPressLong){ + case 1: + // ## switch to MENU state ## + if (lastPressLong) + { + control->changeMode(controlMode_t::MENU); + ESP_LOGW(TAG, "1x long press -> change to menu mode"); + buzzer->beep(1, 1000, 1); + vTaskDelay(500 / portTICK_PERIOD_MS); + } + // ## toggle joystick freeze ## + else if (control->getCurrentMode() == controlMode_t::MASSAGE) + { + control->toggleFreezeInputMassage(); + } + // ## define joystick center ## + else + { + // note: disabled joystick calibration due to accidential trigger + //joystick->defineCenter(); + } + break; + + case 2: + // ## switch to ADJUST_CHAIR mode ## + if (lastPressLong) + { ESP_LOGW(TAG, "cmd %d: toggle ADJUST_CHAIR", count); control->toggleMode(controlMode_t::ADJUST_CHAIR); } - - //toggle idle when 2x pressed + // ## toggle IDLE ## else { ESP_LOGW(TAG, "cmd %d: toggle IDLE", count); control->toggleIdle(); //toggle between idle and previous/default mode @@ -84,21 +92,25 @@ void buttonCommands::action (uint8_t count, bool lastPressLong){ break; case 3: + // ## switch to JOYSTICK mode ## ESP_LOGW(TAG, "cmd %d: switch to JOYSTICK", count); control->changeMode(controlMode_t::JOYSTICK); //switch to JOYSTICK mode break; case 4: + // ## switch to HTTP mode ## ESP_LOGW(TAG, "cmd %d: toggle between HTTP and JOYSTICK", count); control->toggleModes(controlMode_t::HTTP, controlMode_t::JOYSTICK); //toggle between HTTP and JOYSTICK mode break; case 6: + // ## switch to MASSAGE mode ## ESP_LOGW(TAG, "cmd %d: toggle between MASSAGE and JOYSTICK", count); control->toggleModes(controlMode_t::MASSAGE, controlMode_t::JOYSTICK); //toggle between MASSAGE and JOYSTICK mode break; case 8: + // ## toggle "sport-mode" ## //toggle deceleration fading between on and off //decelEnabled = motorLeft->toggleFade(fadeType_t::DECEL); //motorRight->toggleFade(fadeType_t::DECEL); @@ -113,12 +125,10 @@ void buttonCommands::action (uint8_t count, bool lastPressLong){ break; case 12: - ESP_LOGW(TAG, "cmd %d: sending button event to control task", count); - //-> toggle altStickMapping (executed in control task) - control->sendButtonEvent(count); //TODO: always send button event to control task (not just at count=1)? + // ## toggle alternative stick mapping ## + control->toggleAltStickMapping(); break; - - } + } } @@ -127,56 +137,66 @@ void buttonCommands::action (uint8_t count, bool lastPressLong){ //----------------------------- //------ startHandleLoop ------ //----------------------------- -//this function has to be started once in a separate task -//repeatedly evaluates and processes button events then takes the corresponding action -void buttonCommands::startHandleLoop() { +// 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 800 // duration of no button events, after which action is run (implicitly also is 'long-press' time) +void buttonCommands::startHandleLoop() +{ + //-- variables -- + bool isPressed = false; + static rotary_encoder_event_t ev; // store event data + // int count = 0; (from class) - while(1) { - vTaskDelay(20 / portTICK_PERIOD_MS); - //run handle function of evaluatedSwitch object - button->handle(); - - //--- count button presses and run action --- - switch(state) { - case inputState_t::IDLE: //wait for initial button press - if (button->risingEdge) { - count = 1; - buzzer->beep(1, 65, 0); - timestamp_lastAction = esp_log_timestamp(); - state = inputState_t::WAIT_FOR_INPUT; - ESP_LOGI(TAG, "first button press detected -> waiting for further events"); - } - break; - - case inputState_t::WAIT_FOR_INPUT: //wait for further presses - //button pressed again - if (button->risingEdge){ - count++; - buzzer->beep(1, 65, 0); - timestamp_lastAction = esp_log_timestamp(); - ESP_LOGI(TAG, "another press detected -> count=%d -> waiting for further events", count); - } - //timeout - else if (esp_log_timestamp() - timestamp_lastAction > 1000) { - state = inputState_t::IDLE; - buzzer->beep(count, 50, 50); - //TODO: add optional "bool wait" parameter to beep function to delay until finished beeping - ESP_LOGI(TAG, "timeout - running action function for count=%d", count); - //--- run action function --- - //check if still pressed - bool lastPressLong = false; - if (button->state == true){ - //run special case when last press was longer than timeout - lastPressLong = true; - } - //run action function with current count of button presses - action(count, lastPressLong); - } - break; + while (1) + { + //-- disable functionality when in menu mode -- + //(display task uses encoder in that mode) + if (control->getCurrentMode() == controlMode_t::MENU) + { + //do nothing every loop cycle + ESP_LOGD(TAG, "in MENU mode -> button commands disabled"); + vTaskDelay(1000 / portTICK_PERIOD_MS); + continue; } - } -} - - - + //-- get events from encoder -- + if (xQueueReceive(encoderQueue, &ev, INPUT_TIMEOUT / portTICK_PERIOD_MS)) + { + control->resetTimeout(); //reset inactivity IDLE timeout + switch (ev.type) + { + break; + case RE_ET_BTN_PRESSED: + ESP_LOGD(TAG, "Button pressed"); + buzzer->beep(1, 65, 0); + isPressed = true; + count++; // count each pressed event + break; + case RE_ET_BTN_RELEASED: + ESP_LOGD(TAG, "Button released"); + isPressed = false; // rest stored state + break; + case RE_ET_BTN_LONG_PRESSED: + case RE_ET_BTN_CLICKED: + case RE_ET_CHANGED: + default: + break; + } + } + else // timeout (no event received within TIMEOUT) + { + if (count > 0) + { + //-- run action with count of presses -- + ESP_LOGI(TAG, "timeout: count=%d, lastPressLong=%d -> running action", count, isPressed); + buzzer->beep(count, 50, 50); + action(count, isPressed); // run action - if currently still on the last press is considered long + count = 0; // reset count + } + else { + ESP_LOGD(TAG, "no button event received in this cycle (count=0)"); + } + } //end queue + } //end while(1) +} //end function \ No newline at end of file diff --git a/board_single/main/control.cpp b/board_single/main/control.cpp index 5976c70..44646bd 100644 --- a/board_single/main/control.cpp +++ b/board_single/main/control.cpp @@ -20,7 +20,7 @@ extern "C" //tag for logging static const char * TAG = "control"; -const char* controlModeStr[8] = {"IDLE", "JOYSTICK", "MASSAGE", "HTTP", "MQTT", "BLUETOOTH", "AUTO", "ADJUST_CHAIR"}; +const char* controlModeStr[9] = {"IDLE", "JOYSTICK", "MASSAGE", "HTTP", "MQTT", "BLUETOOTH", "AUTO", "ADJUST_CHAIR", "MENU"}; //----------------------------- @@ -183,46 +183,18 @@ void controlledArmchair::startHandleLoop() { break; + case controlMode_t::MENU: + vTaskDelay(1000 / portTICK_PERIOD_MS); + //nothing to do here, display task handles the menu + //--- idle motors --- + commands = cmds_bothMotorsIdle; + motorRight->setTarget(commands.right.state, commands.right.duty); + motorLeft->setTarget(commands.left.state, commands.left.duty); + break; + //TODO: add other modes here } - - //--- run actions based on received button button event --- - //note: buttonCount received by sendButtonEvent method called from button.cpp - //TODO: what if variable gets set from other task during this code? -> mutex around this code - switch (buttonCount) { - case 1: //define joystick center or freeze input - if (mode == controlMode_t::JOYSTICK){ - //joystick mode: calibrate joystick - joystick_l->defineCenter(); - } else if (mode == controlMode_t::MASSAGE){ - //massage mode: toggle freeze of input (lock joystick at current values) - freezeInput = !freezeInput; - if (freezeInput){ - buzzer->beep(5, 40, 25); - } else { - buzzer->beep(1, 300, 100); - } - } - break; - - case 12: //toggle alternative joystick mapping (reverse swapped) - altStickMapping = !altStickMapping; - if (altStickMapping){ - buzzer->beep(6, 70, 50); - } else { - buzzer->beep(1, 500, 100); - } - break; - } - //--- reset button event --- (only one action per run) - if (buttonCount > 0){ - ESP_LOGI(TAG, "resetting button event/count"); - buttonCount = 0; - } - - - //----------------------- //------ slow loop ------ //----------------------- @@ -240,6 +212,60 @@ void controlledArmchair::startHandleLoop() { + +//--------------------------------------- +//------ toggleFreezeInputMassage ------- +//--------------------------------------- +// releases or locks joystick in place when in massage mode +bool controlledArmchair::toggleFreezeInputMassage() +{ + if (mode == controlMode_t::MASSAGE) + { + // massage mode: toggle freeze of input (lock joystick at current values) + freezeInput = !freezeInput; + if (freezeInput) + { + buzzer->beep(5, 40, 25); + ESP_LOGW(TAG, "joystick input is now locked in place"); + } + else + { + buzzer->beep(1, 300, 100); + ESP_LOGW(TAG, "joystick input gets updated again"); + } + return freezeInput; + } + else + { + ESP_LOGE(TAG, "can not freeze/unfreeze joystick input - not in MASSAGE mode!"); + return 0; + } +} + + + +//------------------------------------- +//------- toggleAltStickMapping ------- +//------------------------------------- +// toggle between normal and alternative stick mapping (joystick reverse position inverted) +bool controlledArmchair::toggleAltStickMapping() +{ + altStickMapping = !altStickMapping; + if (altStickMapping) + { + buzzer->beep(6, 70, 50); + ESP_LOGW(TAG, "changed to alternative stick mapping"); + } + else + { + buzzer->beep(1, 500, 100); + ESP_LOGW(TAG, "changed to default stick mapping"); + } + return altStickMapping; +} + + + //----------------------------------- //---------- resetTimeout ----------- //----------------------------------- @@ -250,17 +276,6 @@ void controlledArmchair::resetTimeout(){ -//------------------------------------ -//--------- sendButtonEvent ---------- -//------------------------------------ -void controlledArmchair::sendButtonEvent(uint8_t count){ - //TODO mutex - if not replaced with queue - ESP_LOGI(TAG, "setting button event"); - buttonCount = count; -} - - - //------------------------------------ //---------- handleTimeout ----------- //------------------------------------ diff --git a/board_single/main/control.hpp b/board_single/main/control.hpp index 63b8234..003f299 100644 --- a/board_single/main/control.hpp +++ b/board_single/main/control.hpp @@ -11,9 +11,9 @@ //---- struct, enum, variable declarations --- //-------------------------------------------- //enum that decides how the motors get controlled -enum class controlMode_t {IDLE, JOYSTICK, MASSAGE, HTTP, MQTT, BLUETOOTH, AUTO, ADJUST_CHAIR}; +enum class controlMode_t {IDLE, JOYSTICK, MASSAGE, HTTP, MQTT, BLUETOOTH, AUTO, ADJUST_CHAIR, MENU}; //string array representing the mode enum (for printing the state as string) -extern const char* controlModeStr[8]; +extern const char* controlModeStr[9]; //--- control_config_t --- //struct with config parameters @@ -63,9 +63,15 @@ class controlledArmchair { //function that restarts timer which initiates the automatic timeout (switch to IDLE) after certain time of inactivity void resetTimeout(); - //function for sending a button event (e.g. from button task at event) to control task - //TODO: use queue instead? - void sendButtonEvent(uint8_t count); + //methods to get the current control mode + controlMode_t getCurrentMode() const {return mode;}; + const char *getCurrentModeStr() const { return controlModeStr[(int)mode]; }; + + // releases or locks joystick in place when in massage mode, returns true when input is frozen + bool toggleFreezeInputMassage(); + + // toggle between normal and alternative stick mapping (joystick reverse position inverted), returns true when alt mapping is active + bool toggleAltStickMapping(); private: diff --git a/board_single/main/display.cpp b/board_single/main/display.cpp index cfabf74..5665168 100644 --- a/board_single/main/display.cpp +++ b/board_single/main/display.cpp @@ -1,32 +1,29 @@ #include "display.hpp" extern "C"{ #include +#include "esp_ota_ops.h" } +#include "menu.hpp" -//# -//# SSD1306 Configuration -//# -#define GPIO_RANGE_MAX 33 + + +//==== display config ==== #define I2C_INTERFACE y -//# SSD1306_128x32 is not set -#define SSD1306_128x64 y -#define OFFSETX 0 -//# FLIP is not set #define SCL_GPIO 22 #define SDA_GPIO 23 -#define RESET_GPIO 15 //FIXME remove this -#define I2C_PORT_0 y -//# I2C_PORT_1 is not set -//# end of SSD1306 Configuration +#define RESET_GPIO 15 // FIXME remove this +// the following options are set in menuconfig: (see sdkconfig) +// #define CONFIG_OFFSETX 2 //note: the larger display (actual 130x64) needs 2 pixel offset (prevents bugged column) +// #define CONFIG_I2C_PORT_0 y +//=== content config === +#define STARTUP_MSG_TIMEOUT 2000 #define ADC_BATT_VOLTAGE ADC1_CHANNEL_6 #define BAT_CELL_COUNT 7 - - //-------------------------- //------- getVoltage ------- //-------------------------- @@ -44,24 +41,20 @@ float getVoltage1(adc1_channel_t adc, uint32_t samples){ -//========================== -//======= variables ======== -//========================== +//====================== +//===== variables ====== +//====================== +//display SSD1306_t dev; -//int center, top, bottom; -char lineChar[20]; -//top = 2; -//center = 3; -//bottom = 8; //tag for logging static const char * TAG = "display"; - -//================= -//===== init ====== -//================= +//====================== +//==== display_init ==== +//====================== +//note CONFIG_OFFSETX is used (from menuconfig) void display_init(){ adc1_config_channel_atten(ADC1_CHANNEL_6, ADC_ATTEN_DB_11); //max voltage ESP_LOGW("display", "INTERFACE is i2c"); @@ -81,6 +74,78 @@ void display_init(){ } + +//=============================== +//======= displayTextLine ======= +//=============================== +//abstracted function for printing one line on the display, using a format string directly +//and options: Large-font (3 lines, max 5 digits), or inverted color +void displayTextLine(SSD1306_t *display, int line, bool isLarge, bool inverted, const char *format, ...) +{ + char buf[17]; + int len; + + // format string + arguments to string + va_list args; + va_start(args, format); + len = vsnprintf(buf, sizeof(buf), format, args); + va_end(args); + + // show line on display + if (isLarge) + ssd1306_display_text_x3(display, line, buf, len, inverted); + else + ssd1306_display_text(display, line, buf, len, inverted); +} + + + +//=================================== +//===== displayTextLineCentered ===== +//=================================== +//abstracted function for printing a string CENTERED on the display, using a format string +//adds spaces left and right to fill the line (if not too long already) +#define MAX_LEN_NORMAL 16 //count of available digits on display (normal/large font) +#define MAX_LEN_LARGE 5 +void displayTextLineCentered(SSD1306_t *display, int line, bool isLarge, bool inverted, const char *format, ...) +{ + // variables + char buf[MAX_LEN_NORMAL*2 + 2]; + char tmp[MAX_LEN_NORMAL + 1]; + int len; + + // format string + arguments to string (-> tmp) + va_list args; + va_start(args, format); + len = vsnprintf(tmp, sizeof(tmp), format, args); + va_end(args); + + // define max available digits + int maxLen = MAX_LEN_NORMAL; + if (isLarge) + maxLen = MAX_LEN_LARGE; + + // determine required spaces + int numSpaces = (maxLen - len) / 2; + if (numSpaces < 0) // limit to 0 in case string is too long already + numSpaces = 0; + + // add certain spaces around string (-> buf) + snprintf(buf, MAX_LEN_NORMAL*2, "%*s%s%*s", numSpaces, "", tmp, maxLen - numSpaces - len, ""); + ESP_LOGD(TAG, "print center - isLarge=%d, value='%s', needed-spaces=%d, resulted-string='%s'", isLarge, tmp, numSpaces, buf); + + // show line on display + if (isLarge) + ssd1306_display_text_x3(display, line, buf, maxLen, inverted); + else + ssd1306_display_text(display, line, buf, maxLen, inverted); +} + + + +//---------------------------------- +//------- getBatteryVoltage -------- +//---------------------------------- float getBatteryVoltage(){ #define BAT_VOLTAGE_CONVERSION_FACTOR 11.9 float voltageRead = getVoltage1(ADC_BATT_VOLTAGE, 1000); @@ -99,7 +164,8 @@ float getBatteryVoltage(){ const float voltageLevels[] = {3.00, 3.45, 3.68, 3.74, 3.77, 3.79, 3.82, 3.87, 3.92, 3.98, 4.06, 4.20}; const float percentageLevels[] = {0.0, 5.0, 10.0, 20.0, 30.0, 40.0, 50.0, 60.0, 70.0, 80.0, 90.0, 100.0}; -float getBatteryPercent(float voltage){ +float getBatteryPercent(){ + float voltage = getBatteryVoltage(); float cellVoltage = voltage/BAT_CELL_COUNT; int size = sizeof(voltageLevels) / sizeof(voltageLevels[0]); int sizePer = sizeof(percentageLevels) / sizeof(percentageLevels[0]); @@ -131,9 +197,60 @@ float getBatteryPercent(float voltage){ return 0.0; //unknown range } -float getBatteryPercent(){ - float voltage = getBatteryVoltage(); - return getBatteryPercent(voltage); + + +//----------------------- +//----- showScreen1 ----- +//----------------------- +//shows overview on entire display: +//percentage, voltage, current, mode, rpm, speed +void showScreen1() +{ + //-- battery percentage -- + // TODO update when no load (currentsensors = ~0A) only + //large + displayTextLine(&dev, 0, true, false, "B:%02.0f%%", getBatteryPercent()); + + //-- voltage and current -- + displayTextLine(&dev, 3, false, false, "%04.1fV %04.1f:%04.1fA", + getBatteryVoltage(), + fabs(motorLeft.getCurrentA()), + fabs(motorRight.getCurrentA())); + + //-- control state -- + //print large line + displayTextLine(&dev, 4, true, false, "%s ", control.getCurrentModeStr()); + + //-- speed and RPM -- + displayTextLine(&dev, 7, false, false, "%3.1fkm/h %03.0f:%03.0fR", + fabs((speedLeft.getKmph() + speedRight.getKmph()) / 2), + speedLeft.getRpm(), + speedRight.getRpm()); + + // debug speed sensors + ESP_LOGD(TAG, "%3.1fkm/h %03.0f:%03.0fR", + fabs((speedLeft.getKmph() + speedRight.getKmph()) / 2), + speedLeft.getRpm(), + speedRight.getRpm()); +} + + + +//------------------------ +//---- showStartupMsg ---- +//------------------------ +//shows welcome message and information about current version +void showStartupMsg(){ + const esp_app_desc_t * desc = esp_ota_get_app_description(); + + //show message + displayTextLine(&dev, 0, true, false, "START"); + //show git-tag + displayTextLine(&dev, 4, false, false, "%s", desc->version); + //show build-date (note: date,time of last clean build) + displayTextLine(&dev, 6, false, false, "%s", desc->date); + //show build-time + displayTextLine(&dev, 7, false, false, "%s", desc->time); } @@ -142,70 +259,36 @@ float getBatteryPercent(){ //============================ //======= display task ======= //============================ -#define VERY_SLOW_LOOP_INTERVAL 30000 -#define SLOW_LOOP_INTERVAL 1000 -#define FAST_LOOP_INTERVAL 200 -//TODO: separate taks for each loop? - -void display_task( void * pvParameters ){ - char buf[20]; - char buf1[20]; - int len, len1; - int countFastloop = SLOW_LOOP_INTERVAL; - int countSlowLoop = VERY_SLOW_LOOP_INTERVAL; +#define STATUS_SCREEN_UPDATE_INTERVAL 500 +// TODO: separate task for each loop? +void display_task(void *pvParameters) +{ + // initialize display display_init(); - //TODO check if successfully initialized + // TODO check if successfully initialized - //welcome msg - strcpy(buf, "Hello"); - ssd1306_display_text_x3(&dev, 0, buf, 5, false); - vTaskDelay(1000 / portTICK_PERIOD_MS); + // show startup message + showStartupMsg(); + vTaskDelay(STARTUP_MSG_TIMEOUT / portTICK_PERIOD_MS); + ssd1306_clear_screen(&dev, false); - //update stats - while(1){ - - if (countFastloop >= SLOW_LOOP_INTERVAL / FAST_LOOP_INTERVAL){ - //---- very slow loop ---- - if (countSlowLoop >= VERY_SLOW_LOOP_INTERVAL/SLOW_LOOP_INTERVAL){ - //clear display - workaround for bugged line order after a few minutes - countSlowLoop = 0; - ssd1306_clear_screen(&dev, false); - } - //---- slow loop ---- - countSlowLoop ++; - countFastloop = 0; - //--- battery stats --- - //TODO update only when no load (currentsensors = ~0A) - float battVoltage = getBatteryVoltage(); - float battPercent = getBatteryPercent(battVoltage); - len = snprintf(buf, sizeof(buf), "Bat:%.1fV %.2fV", battVoltage, battVoltage/BAT_CELL_COUNT); - len1 = snprintf(buf1, sizeof(buf1), "B:%02.0f%%", battPercent); - ssd1306_display_text_x3(&dev, 0, buf1, len1, false); - ssd1306_display_text(&dev, 3, buf, len, false); - ssd1306_display_text(&dev, 4, buf, len, true); + // repeatedly update display with content + while (1) + { + if (control.getCurrentMode() == controlMode_t::MENU) + { + //uses encoder events to control menu and updates display + handleMenu(&dev); } - - //---- fast loop ---- - //update speed/rpm - float sLeft = speedLeft.getKmph(); - float rLeft = speedLeft.getRpm(); - float sRight = speedRight.getKmph(); - float rRight = speedRight.getRpm(); - len = snprintf(buf, sizeof(buf), "L:%.1f R:%.1fkm/h", fabs(sLeft), fabs(sRight)); - ssd1306_display_text(&dev, 5, buf, len, false); - len = snprintf(buf, sizeof(buf), "L:%4.0f R:%4.0fRPM", rLeft, rRight); - ssd1306_display_text(&dev, 6, buf, len, false); - //debug speed sensors - ESP_LOGD(TAG, "%s", buf); - //TODO show currentsensor values - - vTaskDelay(FAST_LOOP_INTERVAL / portTICK_PERIOD_MS); - countFastloop++; + else //show status screen in any other mode + { + showScreen1(); + vTaskDelay(STATUS_SCREEN_UPDATE_INTERVAL / portTICK_PERIOD_MS); + } + // TODO add pages and menus } - //TODO add pages and menus - - +} //----------------------------------- //---- text-related example code ---- @@ -309,15 +392,4 @@ void display_task( void * pvParameters ){ //// Fade Out - //ssd1306_fadeout(&dev); - -#if 0 - // Fade Out - for(int contrast=0xff;contrast>0;contrast=contrast-0x20) { - ssd1306_contrast(&dev, contrast); - vTaskDelay(40); - } -#endif - -} - + //ssd1306_fadeout(&dev); \ No newline at end of file diff --git a/board_single/main/display.hpp b/board_single/main/display.hpp index 98c8b79..869435c 100644 --- a/board_single/main/display.hpp +++ b/board_single/main/display.hpp @@ -1,7 +1,10 @@ +#pragma once + extern "C" { #include #include #include +#include #include "freertos/FreeRTOS.h" #include "freertos/task.h" #include "esp_log.h" @@ -16,3 +19,11 @@ extern "C" { //task that inititialized the display, displays welcome message //and releatedly updates the display with certain content void display_task( void * pvParameters ); + +//abstracted function for printing one line on the display, using a format string directly +//and options: Large-font (3 lines, max 5 digits), or inverted color +void displayTextLine(SSD1306_t *display, int line, bool large, bool inverted, const char *format, ...); + +//abstracted function for printing a string CENTERED on the display, using a format string +//adds spaces left and right to fill the line (if not too long already) +void displayTextLineCentered(SSD1306_t *display, int line, bool isLarge, bool inverted, const char *format, ...); \ No newline at end of file diff --git a/board_single/main/encoder.cpp b/board_single/main/encoder.cpp new file mode 100644 index 0000000..d2684e1 --- /dev/null +++ b/board_single/main/encoder.cpp @@ -0,0 +1,83 @@ +extern "C" +{ +#include +#include +#include +#include "freertos/FreeRTOS.h" +#include "freertos/task.h" +#include "driver/gpio.h" +#include "esp_log.h" + +#include "encoder.h" +} + +#include "encoder.hpp" + +//------------------------- +//------- variables ------- +//------------------------- +static const char * TAG = "encoder"; +uint16_t encoderCount; +rotary_encoder_btn_state_t encoderButtonState = {}; +//global event queue: +QueueHandle_t encoderQueue = NULL; + +//encoder config +rotary_encoder_t encoderConfig = { + .pin_a = PIN_A, + .pin_b = PIN_B, + .pin_btn = PIN_BUTTON, + .code = 1, + .store = encoderCount, + .index = 0, + .btn_pressed_time_us = 20000, + .btn_state = encoderButtonState +}; + + + +//================================== +//========== encoder_init ========== +//================================== +//initialize encoder +void encoder_init(){ + encoderQueue = xQueueCreate(QUEUE_SIZE, sizeof(rotary_encoder_event_t)); + rotary_encoder_init(encoderQueue); + rotary_encoder_add(&encoderConfig); +} + + + +//================================== +//====== task_encoderExample ======= +//================================== +//receive and handle all available encoder events +void task_encoderExample(void *arg) { + static rotary_encoder_event_t ev; //store event data + while (1) { + if (xQueueReceive(encoderQueue, &ev, portMAX_DELAY)) { + //log enocder events + switch (ev.type){ + case RE_ET_CHANGED: + ESP_LOGI(TAG, "Event type: RE_ET_CHANGED, diff: %d", ev.diff); + break; + case RE_ET_BTN_PRESSED: + ESP_LOGI(TAG, "Button pressed"); + break; + case RE_ET_BTN_RELEASED: + ESP_LOGI(TAG, "Button released"); + break; + case RE_ET_BTN_CLICKED: + ESP_LOGI(TAG, "Button clicked"); + break; + case RE_ET_BTN_LONG_PRESSED: + ESP_LOGI(TAG, "Button long-pressed"); + break; + default: + ESP_LOGW(TAG, "Unknown event type"); + break; + } + } + } +} + diff --git a/board_single/main/encoder.hpp b/board_single/main/encoder.hpp new file mode 100644 index 0000000..0808d13 --- /dev/null +++ b/board_single/main/encoder.hpp @@ -0,0 +1,20 @@ +extern "C" { +#include "freertos/FreeRTOS.h" // FreeRTOS related headers +#include "freertos/task.h" +#include "encoder.h" +} + +//config +#define QUEUE_SIZE 10 +#define PIN_A GPIO_NUM_25 +#define PIN_B GPIO_NUM_26 +#define PIN_BUTTON GPIO_NUM_27 + +//global encoder queue +extern QueueHandle_t encoderQueue; + +//init encoder with config in encoder.cpp +void encoder_init(); + +//task that handles encoder events +void task_encoderExample(void *arg); diff --git a/board_single/main/main.cpp b/board_single/main/main.cpp index 9b24e78..88cf1f9 100644 --- a/board_single/main/main.cpp +++ b/board_single/main/main.cpp @@ -29,6 +29,7 @@ extern "C" #include "uart_common.hpp" #include "display.hpp" +#include "encoder.hpp" //tag for logging static const char * TAG = "main"; @@ -140,7 +141,7 @@ void setLoglevels(void){ //--- set loglevel for individual tags --- esp_log_level_set("main", ESP_LOG_INFO); - //esp_log_level_set("buzzer", ESP_LOG_INFO); + esp_log_level_set("buzzer", ESP_LOG_ERROR); //esp_log_level_set("motordriver", ESP_LOG_DEBUG); //esp_log_level_set("motor-control", ESP_LOG_INFO); //esp_log_level_set("evaluatedJoystick", ESP_LOG_DEBUG); @@ -155,6 +156,7 @@ void setLoglevels(void){ //esp_log_level_set("current-sensors", ESP_LOG_INFO); //esp_log_level_set("speedSensor", ESP_LOG_INFO); esp_log_level_set("chair-adjustment", ESP_LOG_INFO); + esp_log_level_set("menu", ESP_LOG_INFO); } @@ -173,6 +175,11 @@ extern "C" void app_main(void) { //---- define log levels ---- setLoglevels(); + // init encoder + //--- initialize encoder --- + encoder_init(); + // now global encoderQueue providing all encoder events is available + //---------------------------------------------- //--- create task for controlling the motors --- //---------------------------------------------- diff --git a/board_single/main/menu.cpp b/board_single/main/menu.cpp new file mode 100644 index 0000000..2b99684 --- /dev/null +++ b/board_single/main/menu.cpp @@ -0,0 +1,465 @@ +extern "C"{ +#include +#include +#include "freertos/FreeRTOS.h" +#include "freertos/task.h" +#include "freertos/queue.h" +#include "esp_log.h" + +#include "ssd1306.h" +} + +#include "menu.hpp" +#include "encoder.hpp" +#include "config.hpp" +#include "motorctl.hpp" + + +//--- variables --- +static const char *TAG = "menu"; +static menuState_t menuState = MAIN_MENU; +static int value = 0; + + + +//================================ +//===== CONFIGURE MENU ITEMS ===== +//================================ +// note: when line4 * and line5 * are empty the value is printed large + +//######################### +//#### center Joystick #### +//######################### +void item_centerJoystick_action(int value, SSD1306_t * display){ + if (!value) return; + ESP_LOGW(TAG, "defining joystick center"); + joystick.defineCenter(); +} +int item_centerJoystick_value(){ + return 1; +} + +menuItem_t item_centerJoystick = { + item_centerJoystick_action, // function action + item_centerJoystick_value, + 0, // valueMin + 1, // valueMAx + 1, // valueIncrement + "Center Joystick", // title + "Center Joystick", // line1 (above value) + "click to confirm", // line2 (above value) + "defines current", // line4 * (below value) + "pos as center", // line5 * + "click to confirm", // line6 + "set 0 to cancel", // line7 +}; + + +//######################## +//#### debug Joystick #### +//######################## +//continously show/update joystick data on display +void item_debugJoystick_action(int value, SSD1306_t * display) +{ + //--- variables --- + bool running = true; + rotary_encoder_event_t event; + + //-- pre loop instructions -- + if (!value) // dont open menu when value was set to 0 + return; + ESP_LOGW(TAG, "showing joystick debug page"); + ssd1306_clear_screen(display, false); + // show title + displayTextLine(display, 0, false, true, " - debug stick - "); + // show info line + displayTextLineCentered(display, 7, false, true, "click to exit"); + + //-- show/update values -- + // stop when button pressed or control state changes (timeouts to IDLE) + while (running && control.getCurrentMode() == controlMode_t::MENU) + { + // repeatedly print all joystick data + joystickData_t data = joystick.getData(); + displayTextLine(display, 1, false, false, "x = %.3f ", data.x); + displayTextLine(display, 2, false, false, "y = %.3f ", data.y); + displayTextLine(display, 3, false, false, "radius = %.3f", data.radius); + displayTextLine(display, 4, false, false, "angle = %-06.3f ", data.angle); + displayTextLine(display, 5, false, false, "pos=%-12s ", joystickPosStr[(int)data.position]); + + // exit when button pressed + if (xQueueReceive(encoderQueue, &event, 20 / portTICK_PERIOD_MS)) + { + switch (event.type) + { + case RE_ET_BTN_CLICKED: + running = false; + break; + case RE_ET_CHANGED: + case RE_ET_BTN_PRESSED: + case RE_ET_BTN_RELEASED: + case RE_ET_BTN_LONG_PRESSED: + break; + } + } + } +} + +int item_debugJoystick_value(){ + return 1; +} + +menuItem_t item_debugJoystick = { + item_debugJoystick_action, // function action + item_debugJoystick_value, + 0, // valueMin + 1, // valueMAx + 1, // valueIncrement + "Debug joystick", // title + "Debug joystick", // line1 (above value) + "", // line2 (above value) + "click to enter", // line4 * (below value) + "debug screen", // line5 * + "prints values", // line6 + "set 0 to cancel", // line7 +}; + + +//######################## +//##### set max duty ##### +//######################## +void maxDuty_action(int value, SSD1306_t * display) +{ + //TODO actually store the value + ESP_LOGW(TAG, "set max duty to %d", value); +} +int maxDuty_currentValue() +{ + //TODO get real current value + return 84; +} +menuItem_t item_maxDuty = { + maxDuty_action, // function action + maxDuty_currentValue, + 1, // valueMin + 99, // valueMAx + 1, // valueIncrement + "max duty", // title + "", // line1 (above value) + " set max-duty: ", // line2 (above value) + "", // line4 * (below value) + "", // line5 * + " 1-99 ", // line6 + " percent ", // line7 +}; + +//###################### +//##### accelLimit ##### +//###################### +void item_accelLimit_action(int value, SSD1306_t * display) +{ + motorLeft.setFade(fadeType_t::ACCEL, (uint32_t)value); + motorRight.setFade(fadeType_t::ACCEL, (uint32_t)value); +} +int item_accelLimit_value() +{ + return motorLeft.getFade(fadeType_t::ACCEL); +} +menuItem_t item_accelLimit = { + item_accelLimit_action, // function action + item_accelLimit_value, + 0, // valueMin + 10000, // valueMAx + 100, // valueIncrement + "Accel limit", // title + "Accel limit /", // line1 (above value) + "Fade up time", // line2 (above value) + "", // line4 * (below value) + "", // line5 * + "milliseconds", // line6 + "from 0 to 100%", // line7 +}; + +// ###################### +// ##### decelLimit ##### +// ###################### +void item_decelLimit_action(int value, SSD1306_t * display) +{ + motorLeft.setFade(fadeType_t::DECEL, (uint32_t)value); + motorRight.setFade(fadeType_t::DECEL, (uint32_t)value); +} +int item_decelLimit_value() +{ + return motorLeft.getFade(fadeType_t::DECEL); +} +menuItem_t item_decelLimit = { + item_decelLimit_action, // function action + item_decelLimit_value, + 0, // valueMin + 10000, // valueMAx + 100, // valueIncrement + "Decel limit", // title + "Decel limit /", // line1 (above value) + "Fade down time", // line2 (above value) + "", // line4 * (below value) + "", // line5 * + "milliseconds", // line6 + "from 100 to 0%", // line7 +}; + +//##################### +//###### example ###### +//##################### +void item_example_action(int value, SSD1306_t * display) +{ + return; +} +int item_example_value(){ + return 53; +} +menuItem_t item_example = { + item_example_action, // function action + item_example_value, + -255, // valueMin + 255, // valueMAx + 2, // valueIncrement + "example-item-max", // title + "line 1 - above", // line1 (above value) + "line 2 - above", // line2 (above value) + "line 4 - below", // line4 * (below value) + "line 5 - below", // line5 * + "line 6 - below", // line6 + "line 7 - last", // line7 +}; + +menuItem_t item_last = { + item_example_action, // function action + item_example_value, + -500, // valueMin + 4500, // valueMAx + 50, // valueIncrement + "set large number", // title + "line 1 - above", // line1 (above value) + "line 2 - above", // line2 (above value) + "", // line4 * (below value) + "", // line5 * + "line 6 - below", // line6 + "line 7 - last", // line7 + +}; + +//store all configured menu items in one array +menuItem_t menuItems[] = {item_centerJoystick, item_debugJoystick, item_accelLimit, item_decelLimit, item_example, item_last}; +int itemCount = 6; + + + + +//-------------------------- +//------ showItemList ------ +//-------------------------- +//function that renders main menu to display (one update) +//list of all menu items with currently selected highlighted +#define SELECTED_ITEM_LINE 4 +#define FIRST_ITEM_LINE 1 +#define LAST_ITEM_LINE 7 +void showItemList(SSD1306_t *display, int selectedItem) +{ + //-- show title line -- + displayTextLine(display, 0, false, true, " --- menu --- "); //inverted + + //-- show item list -- + for (int line = FIRST_ITEM_LINE; line <= LAST_ITEM_LINE; line++) + { // loop through all lines + int printItemIndex = selectedItem - SELECTED_ITEM_LINE + line; + // TODO: when reaching end of items, instead of showing "empty" change position of selected item to still use the entire screen + if (printItemIndex < 0 || printItemIndex >= itemCount) // out of range of available items + { + // no item in this line + displayTextLine(display, line, false, false, " -- empty -- "); + } + else + { + if (printItemIndex == selectedItem) + { + // selected item -> add '> ' and print inverted + displayTextLine(display, line, false, true, "> %-14s", menuItems[printItemIndex].title); // inverted + } + else + { + // not the selected item -> print normal + displayTextLine(display, line, false, false, "%-16s", menuItems[printItemIndex].title); + } + } + // logging + ESP_LOGD(TAG, "showItemList: loop - line=%d, item=%d, (selected=%d '%s')", line, printItemIndex, selectedItem, menuItems[selectedItem].title); + } +} + +//--------------------------- +//----- showValueSelect ----- +//--------------------------- +// function that renders value-select screen to display (one update) +// shows configured text of selected item and currently selected value +// TODO show previous value in one line? +// TODO update changed line only (value) +void showValueSelect(SSD1306_t *display, int selectedItem) +{ + //-- show title line -- + displayTextLine(display, 0, false, true, " -- set value -- "); // inverted + + //-- show text above value -- + displayTextLine(display, 1, false, false, "%-16s", menuItems[selectedItem].line1); + displayTextLine(display, 2, false, false, "%-16s", menuItems[selectedItem].line2); + + //-- show value and other configured lines -- + // print value large, if 2 description lines are empty + if (strlen(menuItems[selectedItem].line4) == 0 && strlen(menuItems[selectedItem].line5) == 0) + { + // print large value + line5 and line6 + displayTextLineCentered(display, 3, true, false, "%d", value); //large centered + displayTextLine(display, 6, false, false, "%-16s", menuItems[selectedItem].line6); + displayTextLine(display, 7, false, false, "%-16s", menuItems[selectedItem].line7); + } + else + { + displayTextLineCentered(display, 3, false, false, "%d", value); //centered + // print description lines 4 to 7 + displayTextLine(display, 4, false, false, "%-16s", menuItems[selectedItem].line4); + displayTextLine(display, 5, false, false, "%-16s", menuItems[selectedItem].line5); + displayTextLine(display, 6, false, false, "%-16s", menuItems[selectedItem].line6); + displayTextLine(display, 7, false, false, "%-16s", menuItems[selectedItem].line7); + } +} + + + + +//======================== +//====== handleMenu ====== +//======================== +//controls menu with encoder input and displays the text on oled display +//function is repeatedly called by display task when in menu state +#define QUEUE_TIMEOUT 3000 //timeout no encoder event - to handle timeout and not block the display loop +#define MENU_TIMEOUT 60000 //inactivity timeout (switch to IDLE mode) +void handleMenu(SSD1306_t *display) +{ + static uint32_t lastActivity = 0; + static int selectedItem = 0; + rotary_encoder_event_t event; // store event data + + //--- handle different menu states --- + switch (menuState) + { + //------------------------- + //---- State MAIN MENU ---- + //------------------------- + case MAIN_MENU: + // update display + showItemList(display, selectedItem); // shows list of items with currently selected one on display + // wait for encoder event + if (xQueueReceive(encoderQueue, &event, QUEUE_TIMEOUT / portTICK_PERIOD_MS)) + { + lastActivity = esp_log_timestamp(); + switch (event.type) + { + case RE_ET_CHANGED: + //--- scroll in list --- + if (event.diff < 0) + { + if (selectedItem != itemCount - 1) + selectedItem++; + ESP_LOGD(TAG, "showing next item: %d '%s'", selectedItem, menuItems[selectedItem].title); + //note: display will update at start of next run + } + else + { + if (selectedItem != 0) + selectedItem--; + ESP_LOGD(TAG, "showing previous item: %d '%s'", selectedItem, menuItems[selectedItem].title); + //note: display will update at start of next run + } + break; + + case RE_ET_BTN_CLICKED: + //--- switch to edit value page --- + ESP_LOGI(TAG, "Button pressed - switching to state SET_VALUE"); + // change state (menu to set value) + menuState = SET_VALUE; + // get currently configured value + value = menuItems[selectedItem].currentValue(); + // clear display + ssd1306_clear_screen(display, false); + break; + + //exit menu mode + case RE_ET_BTN_LONG_PRESSED: + //change to previous mode (e.g. JOYSTICK) + control.toggleMode(controlMode_t::MENU); //currently already in MENU -> changes to previous mode + ssd1306_clear_screen(display, false); + break; + + case RE_ET_BTN_RELEASED: + case RE_ET_BTN_PRESSED: + break; + } + } + break; + + //------------------------- + //---- State SET VALUE ---- + //------------------------- + case SET_VALUE: + // wait for encoder event + showValueSelect(display, selectedItem); + + if (xQueueReceive(encoderQueue, &event, QUEUE_TIMEOUT / portTICK_PERIOD_MS)) + { + lastActivity = esp_log_timestamp(); + switch (event.type) + { + case RE_ET_CHANGED: + //-- change value -- + // increment value + if (event.diff < 0) + value += menuItems[selectedItem].valueIncrement; + else + value -= menuItems[selectedItem].valueIncrement; + // limit to min/max range + if (value > menuItems[selectedItem].valueMax) + value = menuItems[selectedItem].valueMax; + if (value < menuItems[selectedItem].valueMin) + value = menuItems[selectedItem].valueMin; + break; + case RE_ET_BTN_CLICKED: + //-- apply value -- + ESP_LOGI(TAG, "Button pressed - running action function with value=%d for item '%s'", value, menuItems[selectedItem].title); + menuItems[selectedItem].action(value, display); + menuState = MAIN_MENU; + break; + case RE_ET_BTN_PRESSED: + case RE_ET_BTN_RELEASED: + case RE_ET_BTN_LONG_PRESSED: + break; + } + } + break; + } + + + //-------------------- + //--- menu timeout --- + //-------------------- + //close menu and switch to IDLE mode when no encoder event within MENU_TIMEOUT + if (esp_log_timestamp() - lastActivity > MENU_TIMEOUT) + { + ESP_LOGW(TAG, "TIMEOUT - no activity for more than %ds -> closing menu, switching to IDLE", MENU_TIMEOUT/1000); + // reset menu + selectedItem = 0; + menuState = MAIN_MENU; + ssd1306_clear_screen(display, false); + // change control mode + control.changeMode(controlMode_t::IDLE); + return; + } +} \ No newline at end of file diff --git a/board_single/main/menu.hpp b/board_single/main/menu.hpp new file mode 100644 index 0000000..6b86e47 --- /dev/null +++ b/board_single/main/menu.hpp @@ -0,0 +1,32 @@ +#pragma once + +#include "display.hpp" + + +//--- menuState_t --- +// modes the menu can be in +typedef enum { + MAIN_MENU = 0, + SET_VALUE +} menuState_t; + + +//--- menuItem_t --- +// struct describes one menu element (all defined in menu.cpp) +typedef struct { + void (*action)(int value, SSD1306_t * display); // pointer to function run when confirmed + int (*currentValue)(); // pointer to function to get currently configured value + int valueMin; // min allowed value + int valueMax; // max allowed value + int valueIncrement; // amount changed at one encoder tick (+/-) + const char title[17]; // shown in list + const char line1[17]; // above value + const char line2[17]; // above value + const char line4[17]; // below value * + const char line5[17]; // below value * + const char line6[17]; // below value + const char line7[17]; // below value +} menuItem_t; + + +void handleMenu(SSD1306_t * display); \ No newline at end of file diff --git a/common/motorctl.cpp b/common/motorctl.cpp index 1ff8417..67ee009 100644 --- a/common/motorctl.cpp +++ b/common/motorctl.cpp @@ -277,6 +277,24 @@ motorCommand_t controlledMotor::getStatus(){ +//=============================== +//=========== getFade =========== +//=============================== +//return currently configured accel / decel time +uint32_t controlledMotor::getFade(fadeType_t fadeType){ + switch(fadeType){ + case fadeType_t::ACCEL: + return msFadeAccel; + break; + case fadeType_t::DECEL: + return msFadeDecel; + break; + } + return 0; +} + + + //=============================== //=========== setFade =========== //=============================== @@ -287,9 +305,11 @@ void controlledMotor::setFade(fadeType_t fadeType, uint32_t msFadeNew){ //TODO: mutex for msFade variable also used in handle function switch(fadeType){ case fadeType_t::ACCEL: + ESP_LOGW(TAG, "changed fade-up time from %d to %d", msFadeAccel, msFadeNew); msFadeAccel = msFadeNew; break; case fadeType_t::DECEL: + ESP_LOGW(TAG, "changed fade-down time from %d to %d", msFadeDecel, msFadeNew); msFadeDecel = msFadeNew; break; } diff --git a/common/motorctl.hpp b/common/motorctl.hpp index bea2060..adeb840 100644 --- a/common/motorctl.hpp +++ b/common/motorctl.hpp @@ -33,9 +33,12 @@ class controlledMotor { void setTarget(motorstate_t state_f, float duty_f = 0); //adds target command to queue for handle function motorCommand_t getStatus(); //get current status of the motor (returns struct with state and duty) + uint32_t getFade(fadeType_t fadeType); //get currently set acceleration or deceleration fading time void setFade(fadeType_t fadeType, bool enabled); //enable/disable acceleration or deceleration fading void setFade(fadeType_t fadeType, uint32_t msFadeNew); //set acceleration or deceleration fade time bool toggleFade(fadeType_t fadeType); //toggle acceleration or deceleration on/off + + float getCurrentA() {return cSensor.read();}; //read current-sensor of this motor (Ampere) //TODO set current limit method @@ -53,6 +56,7 @@ class controlledMotor { motorSetCommandFunc_t motorSetCommand; //--- variables --- + //TODO add name for logging? //struct for storing control specific parameters motorctl_config_t config; motorstate_t state = motorstate_t::IDLE; diff --git a/components/encoder/.eil.yml b/components/encoder/.eil.yml new file mode 100644 index 0000000..d741eb2 --- /dev/null +++ b/components/encoder/.eil.yml @@ -0,0 +1,21 @@ +name: encoder +description: HW timer-based driver for incremental rotary encoders +version: 1.0.0 +groups: + - input +code_owners: + - UncleRus +depends: + - driver + - freertos + - log +thread_safe: yes +targets: + - esp32 + - esp8266 + - esp32s2 + - esp32c3 +license: BSD-3 +copyrights: + - name: UncleRus + year: 2019 diff --git a/components/encoder/CMakeLists.txt b/components/encoder/CMakeLists.txt new file mode 100644 index 0000000..0dc9a93 --- /dev/null +++ b/components/encoder/CMakeLists.txt @@ -0,0 +1,13 @@ +if(${IDF_TARGET} STREQUAL esp8266) + set(req esp8266 freertos log esp_timer) +elseif(${IDF_VERSION_MAJOR} STREQUAL 4 AND ${IDF_VERSION_MINOR} STREQUAL 1 AND ${IDF_VERSION_PATCH} STREQUAL 3) + set(req driver freertos log) +else() + set(req driver freertos log esp_timer) +endif() + +idf_component_register( + SRCS encoder.c + INCLUDE_DIRS . + REQUIRES ${req} +) diff --git a/components/encoder/Kconfig b/components/encoder/Kconfig new file mode 100644 index 0000000..5ef2a56 --- /dev/null +++ b/components/encoder/Kconfig @@ -0,0 +1,27 @@ +menu "Rotary encoders" + + config RE_MAX + int "Maximum number of rotary encoders" + default 1 + + config RE_INTERVAL_US + int "Polling interval, us" + default 1000 + + config RE_BTN_DEAD_TIME_US + int "Button dead time, us" + default 10000 + + choice RE_BTN_PRESSED_LEVEL + prompt "Logical level on pressed button" + config RE_BTN_PRESSED_LEVEL_0 + bool "0" + config RE_BTN_PRESSED_LEVEL_1 + bool "1" + endchoice + + config RE_BTN_LONG_PRESS_TIME_US + int "Long press timeout, us" + default 500000 + +endmenu diff --git a/components/encoder/LICENSE b/components/encoder/LICENSE new file mode 100644 index 0000000..b280b32 --- /dev/null +++ b/components/encoder/LICENSE @@ -0,0 +1,26 @@ +Copyright 2019 Ruslan V. Uss + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, +this list of conditions and the following disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, +this list of conditions and the following disclaimer in the documentation +and/or other materials provided with the distribution. + +3. Neither the name of the copyright holder nor the names of itscontributors +may be used to endorse or promote products derived from this software without +specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. \ No newline at end of file diff --git a/components/encoder/component.mk b/components/encoder/component.mk new file mode 100644 index 0000000..a03513e --- /dev/null +++ b/components/encoder/component.mk @@ -0,0 +1,7 @@ +COMPONENT_ADD_INCLUDEDIRS = . + +ifdef CONFIG_IDF_TARGET_ESP8266 +COMPONENT_DEPENDS = esp8266 freertos log +else +COMPONENT_DEPENDS = driver freertos log +endif diff --git a/components/encoder/encoder.c b/components/encoder/encoder.c new file mode 100644 index 0000000..06b64e8 --- /dev/null +++ b/components/encoder/encoder.c @@ -0,0 +1,250 @@ +/* + * Copyright (c) 2019 Ruslan V. Uss + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder nor the names of itscontributors + * may be used to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +/** + * @file encoder.c + * + * ESP-IDF HW timer-based driver for rotary encoders + * + * Copyright (c) 2019 Ruslan V. Uss + * + * BSD Licensed as described in the file LICENSE + */ +#include "encoder.h" +#include +#include +#include +#include + +#define MUTEX_TIMEOUT 10 + +#ifdef CONFIG_RE_BTN_PRESSED_LEVEL_0 +#define BTN_PRESSED_LEVEL 0 +#else +#define BTN_PRESSED_LEVEL 1 +#endif + +static const char *TAG = "encoder"; +static rotary_encoder_t *encs[CONFIG_RE_MAX] = { 0 }; +static const int8_t valid_states[] = { 0, 1, 1, 0, 1, 0, 0, 1, 1, 0, 0, 1, 0, 1, 1, 0 }; +static SemaphoreHandle_t mutex; +static QueueHandle_t _queue; + +#define GPIO_BIT(x) ((x) < 32 ? BIT(x) : ((uint64_t)(((uint64_t)1)<<(x)))) +#define CHECK(x) do { esp_err_t __; if ((__ = x) != ESP_OK) return __; } while (0) +#define CHECK_ARG(VAL) do { if (!(VAL)) return ESP_ERR_INVALID_ARG; } while (0) + +inline static void read_encoder(rotary_encoder_t *re) +{ + rotary_encoder_event_t ev = { + .sender = re + }; + + if (re->pin_btn < GPIO_NUM_MAX) + do + { + if (re->btn_state == RE_BTN_PRESSED && re->btn_pressed_time_us < CONFIG_RE_BTN_DEAD_TIME_US) + { + // Dead time + re->btn_pressed_time_us += CONFIG_RE_INTERVAL_US; + break; + } + + // read button state + if (gpio_get_level(re->pin_btn) == BTN_PRESSED_LEVEL) + { + if (re->btn_state == RE_BTN_RELEASED) + { + // first press + re->btn_state = RE_BTN_PRESSED; + re->btn_pressed_time_us = 0; + ev.type = RE_ET_BTN_PRESSED; + xQueueSendToBack(_queue, &ev, 0); + break; + } + + re->btn_pressed_time_us += CONFIG_RE_INTERVAL_US; + + if (re->btn_state == RE_BTN_PRESSED && re->btn_pressed_time_us >= CONFIG_RE_BTN_LONG_PRESS_TIME_US) + { + // Long press + re->btn_state = RE_BTN_LONG_PRESSED; + ev.type = RE_ET_BTN_LONG_PRESSED; + xQueueSendToBack(_queue, &ev, 0); + } + } + else if (re->btn_state != RE_BTN_RELEASED) + { + bool clicked = re->btn_state == RE_BTN_PRESSED; + // released + re->btn_state = RE_BTN_RELEASED; + ev.type = RE_ET_BTN_RELEASED; + xQueueSendToBack(_queue, &ev, 0); + if (clicked) + { + ev.type = RE_ET_BTN_CLICKED; + xQueueSendToBack(_queue, &ev, 0); + } + } + } while(0); + + re->code <<= 2; + re->code |= gpio_get_level(re->pin_a); + re->code |= gpio_get_level(re->pin_b) << 1; + re->code &= 0xf; + + if (!valid_states[re->code]) + return; + + int8_t inc = 0; + + re->store = (re->store << 4) | re->code; + + if (re->store == 0xe817) inc = 1; + if (re->store == 0xd42b) inc = -1; + + if (inc) + { + ev.type = RE_ET_CHANGED; + ev.diff = inc; + xQueueSendToBack(_queue, &ev, 0); + } +} + +static void timer_handler(void *arg) +{ + if (!xSemaphoreTake(mutex, 0)) + return; + + for (size_t i = 0; i < CONFIG_RE_MAX; i++) + if (encs[i]) + read_encoder(encs[i]); + + xSemaphoreGive(mutex); +} + +static const esp_timer_create_args_t timer_args = { + .name = "__encoder__", + .arg = NULL, + .callback = timer_handler, + .dispatch_method = ESP_TIMER_TASK +}; + +static esp_timer_handle_t timer; + +esp_err_t rotary_encoder_init(QueueHandle_t queue) +{ + CHECK_ARG(queue); + _queue = queue; + + mutex = xSemaphoreCreateMutex(); + if (!mutex) + { + ESP_LOGE(TAG, "Failed to create mutex"); + return ESP_ERR_NO_MEM; + } + + CHECK(esp_timer_create(&timer_args, &timer)); + CHECK(esp_timer_start_periodic(timer, CONFIG_RE_INTERVAL_US)); + + ESP_LOGI(TAG, "Initialization complete, timer interval: %dms", CONFIG_RE_INTERVAL_US / 1000); + return ESP_OK; +} + +esp_err_t rotary_encoder_add(rotary_encoder_t *re) +{ + CHECK_ARG(re); + if (!xSemaphoreTake(mutex, MUTEX_TIMEOUT)) + { + ESP_LOGE(TAG, "Failed to take mutex"); + return ESP_ERR_INVALID_STATE; + } + + bool ok = false; + for (size_t i = 0; i < CONFIG_RE_MAX; i++) + if (!encs[i]) + { + re->index = i; + encs[i] = re; + ok = true; + break; + } + if (!ok) + { + ESP_LOGE(TAG, "Too many encoders"); + xSemaphoreGive(mutex); + return ESP_ERR_NO_MEM; + } + + // setup GPIO + gpio_config_t io_conf; + memset(&io_conf, 0, sizeof(gpio_config_t)); + io_conf.mode = GPIO_MODE_INPUT; + if (BTN_PRESSED_LEVEL == 0) { + io_conf.pull_up_en = GPIO_PULLUP_ENABLE; + io_conf.pull_down_en = GPIO_PULLDOWN_DISABLE; + } else { + io_conf.pull_up_en = GPIO_PULLUP_DISABLE; + io_conf.pull_down_en = GPIO_PULLDOWN_ENABLE; + } + io_conf.intr_type = GPIO_INTR_DISABLE; + io_conf.pin_bit_mask = GPIO_BIT(re->pin_a) | GPIO_BIT(re->pin_b); + if (re->pin_btn < GPIO_NUM_MAX) + io_conf.pin_bit_mask |= GPIO_BIT(re->pin_btn); + CHECK(gpio_config(&io_conf)); + + re->btn_state = RE_BTN_RELEASED; + re->btn_pressed_time_us = 0; + + xSemaphoreGive(mutex); + + ESP_LOGI(TAG, "Added rotary encoder %d, A: %d, B: %d, BTN: %d", re->index, re->pin_a, re->pin_b, re->pin_btn); + return ESP_OK; +} + +esp_err_t rotary_encoder_remove(rotary_encoder_t *re) +{ + CHECK_ARG(re); + if (!xSemaphoreTake(mutex, MUTEX_TIMEOUT)) + { + ESP_LOGE(TAG, "Failed to take mutex"); + return ESP_ERR_INVALID_STATE; + } + + for (size_t i = 0; i < CONFIG_RE_MAX; i++) + if (encs[i] == re) + { + encs[i] = NULL; + ESP_LOGI(TAG, "Removed rotary encoder %d", i); + xSemaphoreGive(mutex); + return ESP_OK; + } + + ESP_LOGE(TAG, "Unknown encoder"); + xSemaphoreGive(mutex); + return ESP_ERR_NOT_FOUND; +} diff --git a/components/encoder/encoder.h b/components/encoder/encoder.h new file mode 100644 index 0000000..fc672c8 --- /dev/null +++ b/components/encoder/encoder.h @@ -0,0 +1,125 @@ +/* + * Copyright (c) 2019 Ruslan V. Uss + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder nor the names of itscontributors + * may be used to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +/** + * @file encoder.h + * @defgroup encoder encoder + * @{ + * + * ESP-IDF HW timer-based driver for rotary encoders + * + * Copyright (c) 2019 Ruslan V. Uss + * + * BSD Licensed as described in the file LICENSE + */ +#ifndef __ENCODER_H__ +#define __ENCODER_H__ + +#include +#include +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + + +/** + * Button state + */ +typedef enum { + RE_BTN_RELEASED = 0, //!< Button currently released + RE_BTN_PRESSED = 1, //!< Button currently pressed + RE_BTN_LONG_PRESSED = 2 //!< Button currently long pressed +} rotary_encoder_btn_state_t; + +/** + * Rotary encoder descriptor + */ +typedef struct +{ + gpio_num_t pin_a, pin_b, pin_btn; //!< Encoder pins. pin_btn can be >= GPIO_NUM_MAX if no button used + uint8_t code; + uint16_t store; + size_t index; + uint64_t btn_pressed_time_us; + rotary_encoder_btn_state_t btn_state; +} rotary_encoder_t; + +/** + * Event type + */ +typedef enum { + RE_ET_CHANGED = 0, //!< Encoder turned + RE_ET_BTN_RELEASED, //!< Button released + RE_ET_BTN_PRESSED, //!< Button pressed + RE_ET_BTN_LONG_PRESSED, //!< Button long pressed (press time (us) > RE_BTN_LONG_PRESS_TIME_US) + RE_ET_BTN_CLICKED //!< Button was clicked +} rotary_encoder_event_type_t; + +/** + * Event + */ +typedef struct +{ + rotary_encoder_event_type_t type; //!< Event type + rotary_encoder_t *sender; //!< Pointer to descriptor + int32_t diff; //!< Difference between new and old positions (only if type == RE_ET_CHANGED) +} rotary_encoder_event_t; + +/** + * @brief Initialize library + * + * @param queue Event queue to send encoder events + * @return `ESP_OK` on success + */ +esp_err_t rotary_encoder_init(QueueHandle_t queue); + +/** + * @brief Add new rotary encoder + * + * @param re Encoder descriptor + * @return `ESP_OK` on success + */ +esp_err_t rotary_encoder_add(rotary_encoder_t *re); + +/** + * @brief Remove previously added rotary encoder + * + * @param re Encoder descriptor + * @return `ESP_OK` on success + */ +esp_err_t rotary_encoder_remove(rotary_encoder_t *re); + +#ifdef __cplusplus +} +#endif + +/**@}*/ + +#endif /* __ENCODER_H__ */