diff --git a/board_control/main/CMakeLists.txt b/board_control/main/CMakeLists.txt index 72a232c..575bfc2 100644 --- a/board_control/main/CMakeLists.txt +++ b/board_control/main/CMakeLists.txt @@ -2,14 +2,12 @@ idf_component_register( SRCS "main.cpp" "config.cpp" - "joystick.cpp" "control.cpp" "button.cpp" - "http.cpp" "auto.cpp" "uart.cpp" INCLUDE_DIRS "." ) -spiffs_create_partition_image(spiffs ../react-app/build FLASH_IN_PROJECT) +spiffs_create_partition_image(spiffs ../../react-app/build FLASH_IN_PROJECT) diff --git a/board_motorctl/main/CMakeLists.txt b/board_motorctl/main/CMakeLists.txt index 4b2b42c..f6c8f85 100644 --- a/board_motorctl/main/CMakeLists.txt +++ b/board_motorctl/main/CMakeLists.txt @@ -1,11 +1,8 @@ idf_component_register( SRCS "main.cpp" - "motordrivers.cpp" - "motorctl.cpp" "config.cpp" "fan.cpp" - "currentsensor.cpp" "uart.cpp" INCLUDE_DIRS "." diff --git a/board_motorctl/main/main.cpp b/board_motorctl/main/main.cpp index 4b527c3..c3b6870 100644 --- a/board_motorctl/main/main.cpp +++ b/board_motorctl/main/main.cpp @@ -14,12 +14,20 @@ extern "C" #include "driver/ledc.h" -//custom C files + //custom C files #include "wifi.h" } //custom C++ files #include "config.hpp" #include "uart.hpp" +#include "speedsensor.hpp" + + +//============================ +//======= TESTING MODE ======= +//============================ +//do not start the actual tasks for controlling the armchair +#define TESTING_MODE //========================= //======= UART TEST ======= @@ -32,14 +40,18 @@ extern "C" //======= BRAKE TEST ======= //========================== //only run brake-test (ignore uart input) -#define BRAKE_TEST_ONLY +//#define BRAKE_TEST_ONLY +//====================-====== +//==== SPEED SENSOR TEST ==== +//======================-==== +//only run speed-sensor test +#define SPEED_SENSOR_TEST //tag for logging static const char * TAG = "main"; -#ifndef UART_TEST_ONLY //==================================== //========== motorctl task =========== //==================================== @@ -110,22 +122,25 @@ void setLoglevels(void){ esp_log_level_set("uart_common", ESP_LOG_INFO); esp_log_level_set("uart", ESP_LOG_INFO); //esp_log_level_set("current-sensors", ESP_LOG_INFO); + esp_log_level_set("speedSensor", ESP_LOG_WARN); } -#endif + //================================= //=========== app_main ============ //================================= extern "C" void app_main(void) { -#ifndef UART_TEST_ONLY + + //---- define log levels ---- + setLoglevels(); + +#ifndef TESTING_MODE //enable 5V volate regulator gpio_pad_select_gpio(GPIO_NUM_17); gpio_set_direction(GPIO_NUM_17, GPIO_MODE_OUTPUT); gpio_set_level(GPIO_NUM_17, 1); - //---- define log levels ---- - setLoglevels(); //---------------------------------------------- //--- create task for controlling the motors --- @@ -152,20 +167,42 @@ extern "C" void app_main(void) { +#ifndef BRAKE_TEST_ONLY //------------------------------------------- //--- create tasks for uart communication --- //------------------------------------------- -#ifndef BRAKE_TEST_ONLY uart_init(); xTaskCreate(task_uartReceive, "task_uartReceive", 4096, NULL, 10, NULL); xTaskCreate(task_uartSend, "task_uartSend", 4096, NULL, 10, NULL); #endif - //--- main loop --- + +#ifdef SPEED_SENSOR_TEST + speedSensor_config_t speedRight_config{ + .gpioPin = GPIO_NUM_18, + .degreePerGroup = 72, + .tireCircumferenceMeter = 0.69, + .directionInverted = false, + .logName = "speedRight", + }; + speedSensor speedRight (speedRight_config); +#endif + + + //--------------------------- + //-------- main loop -------- + //--------------------------- //does nothing except for testing things while(1){ - vTaskDelay(500 / portTICK_PERIOD_MS); + +#ifdef SPEED_SENSOR_TEST + vTaskDelay(100 / portTICK_PERIOD_MS); + //speedRight.getRpm(); + ESP_LOGI(TAG, "speedsensor-test: rpm=%fRPM, speed=%fkm/h dir=%d, pulseCount=%d, p1=%d, p2=%d, p3=%d lastEdgetime=%d", speedRight.getRpm(), speedRight.getKmph(), speedRight.direction, speedRight.pulseCounter, (int)speedRight.pulseDurations[0]/1000, (int)speedRight.pulseDurations[1]/1000, (int)speedRight.pulseDurations[2]/1000,(int)speedRight.lastEdgeTime); +#endif + + #ifdef BRAKE_TEST_ONLY //test relays at standstill ESP_LOGW("brake-test", "test relays via motorctl"); @@ -198,7 +235,6 @@ extern "C" void app_main(void) { vTaskDelay(5000 / portTICK_PERIOD_MS); //reset to idle motorRight.setTarget(motorstate_t::IDLE, 0); - #endif diff --git a/board_motorctl/main/motordrivers.cpp b/board_motorctl/main/motordrivers.cpp deleted file mode 100644 index 580db57..0000000 --- a/board_motorctl/main/motordrivers.cpp +++ /dev/null @@ -1,167 +0,0 @@ -#include "motordrivers.hpp" -#include "esp_log.h" -#include "types.hpp" - -//TODO: move from ledc to mcpwm? -//https://docs.espressif.com/projects/esp-idf/en/v4.3/esp32/api-reference/peripherals/mcpwm.html# -//https://github.com/espressif/esp-idf/tree/v4.3/examples/peripherals/mcpwm/mcpwm_basic_config - -//Note fade functionality provided by LEDC would be very useful but unfortunately is not usable here because: -//"Due to hardware limitations, there is no way to stop a fade before it reaches its target duty." - -//tag for logging -static const char * TAG = "motordriver"; - -//ms to wait in IDLE before BRAKE until relay actually switched -#define BRAKE_RELAY_DELAY_MS 300 - - -//==================================== -//===== single100a motor driver ====== -//==================================== - -//----------------------------- -//-------- constructor -------- -//----------------------------- -//copy provided struct with all configuration and run init function -single100a::single100a(single100a_config_t config_f){ - config = config_f; - init(); -} - - - -//---------------------------- -//---------- init ------------ -//---------------------------- -//function to initialize pwm output, gpio pins and calculate maxDuty -void single100a::init(){ - - //--- configure ledc timer --- - ledc_timer_config_t ledc_timer; - ledc_timer.speed_mode = LEDC_HIGH_SPEED_MODE; - ledc_timer.timer_num = config.ledc_timer; - ledc_timer.duty_resolution = config.resolution; //13bit gives max 5khz freq - ledc_timer.freq_hz = config.pwmFreq; - ledc_timer.clk_cfg = LEDC_AUTO_CLK; - //apply configuration - ledc_timer_config(&ledc_timer); - - //--- configure ledc channel --- - ledc_channel_config_t ledc_channel; - ledc_channel.channel = config.ledc_channel; - ledc_channel.duty = 0; - ledc_channel.gpio_num = config.gpio_pwm; - ledc_channel.speed_mode = LEDC_HIGH_SPEED_MODE; - ledc_channel.hpoint = 0; - ledc_channel.timer_sel = config.ledc_timer; - ledc_channel.intr_type = LEDC_INTR_DISABLE; - ledc_channel.flags.output_invert = 0; //TODO: add config option to invert the pwm output? - //apply configuration - ledc_channel_config(&ledc_channel); - - //--- define gpio pins as outputs --- - gpio_pad_select_gpio(config.gpio_a); - gpio_set_direction(config.gpio_a, GPIO_MODE_OUTPUT); - gpio_pad_select_gpio(config.gpio_b); - gpio_set_direction(config.gpio_b, GPIO_MODE_OUTPUT); - gpio_pad_select_gpio(config.gpio_brakeRelay); - gpio_set_direction(config.gpio_brakeRelay, GPIO_MODE_OUTPUT); - - //--- calculate max duty according to selected resolution --- - dutyMax = pow(2, ledc_timer.duty_resolution) -1; - ESP_LOGW(TAG, "initialized single100a driver"); - ESP_LOGW(TAG, "resolution=%dbit, dutyMax value=%d, resolution=%.4f %%", ledc_timer.duty_resolution, dutyMax, 100/(float)dutyMax); -} - - - -//--------------------------- -//----------- set ----------- -//--------------------------- -//function to put the h-bridge module in the desired state and duty cycle -void single100a::set(motorstate_t state_f, float duty_f){ - - //scale provided target duty in percent to available resolution for ledc - uint32_t dutyScaled; - if (duty_f > 100) { //target duty above 100% - dutyScaled = dutyMax; - } else if (duty_f < 0) { //target at or below 0% - state_f = motorstate_t::IDLE; - dutyScaled = 0; - } else { //target duty 0-100% - //scale duty to available resolution - dutyScaled = duty_f / 100 * dutyMax; - } - - ESP_LOGV(TAG, "target-state=%s, duty=%d/%d, duty_input=%.3f%%", motorstateStr[(int)state_f], dutyScaled, dutyMax, duty_f); - - //TODO: only when previous mode was BRAKE? - if (state_f != motorstate_t::BRAKE){ - //reset brake wait state - brakeWaitingForRelay = false; - //turn of brake relay - gpio_set_level(config.gpio_brakeRelay, 0); - } - - //put the single100a h-bridge module in the desired state update duty-cycle - //TODO maybe outsource mode code from once switch case? e.g. idle() brake()... - switch (state_f){ - case motorstate_t::IDLE: - ledc_set_duty(LEDC_HIGH_SPEED_MODE, config.ledc_channel, dutyScaled); - ledc_update_duty(LEDC_HIGH_SPEED_MODE, config.ledc_channel); - //TODO: to fix bugged state of h-bridge module when idle and start again, maybe try to leave pwm signal on for some time before updating a/b pins? - //no brake: (freewheel) - //gpio_set_level(config.gpio_a, config.aEnabledPinState); - //gpio_set_level(config.gpio_b, !config.bEnabledPinState); - gpio_set_level(config.gpio_a, config.aEnabledPinState); - gpio_set_level(config.gpio_b, config.bEnabledPinState); - break; - - case motorstate_t::BRAKE: - //prevent full short (no brake resistors) due to slow relay, also reduces switching load - if (!brakeWaitingForRelay){ - ESP_LOGW(TAG, "BRAKE: turned on relay, waiting in IDLE for %d ms, then apply brake", BRAKE_RELAY_DELAY_MS); - //switch driver to IDLE for now - gpio_set_level(config.gpio_a, config.aEnabledPinState); - gpio_set_level(config.gpio_b, config.bEnabledPinState); - //start brake relay - gpio_set_level(config.gpio_brakeRelay, 1); - timestamp_brakeRelayPowered = esp_log_timestamp(); - brakeWaitingForRelay = true; - } - //check if delay for relay to switch has passed - else if ((esp_log_timestamp() - timestamp_brakeRelayPowered) > BRAKE_RELAY_DELAY_MS) { - ESP_LOGD(TAG, "applying brake with brake-resistors at duty=%.2f%%", duty_f); - //switch driver to BRAKE - gpio_set_level(config.gpio_a, !config.aEnabledPinState); - gpio_set_level(config.gpio_b, !config.bEnabledPinState); - //apply duty - //FIXME switch between BREAK and IDLE with PWM and ignore pwm-pin? (needs test) - ledc_set_duty(LEDC_HIGH_SPEED_MODE, config.ledc_channel, dutyScaled); - ledc_update_duty(LEDC_HIGH_SPEED_MODE, config.ledc_channel); - } else { - //waiting... stay in IDLE - ESP_LOGD(TAG, "waiting for brake relay to close (IDLE)..."); - gpio_set_level(config.gpio_a, config.aEnabledPinState); - gpio_set_level(config.gpio_b, config.bEnabledPinState); - } - break; - - case motorstate_t::FWD: - ledc_set_duty(LEDC_HIGH_SPEED_MODE, config.ledc_channel, dutyScaled); - ledc_update_duty(LEDC_HIGH_SPEED_MODE, config.ledc_channel); - //forward: - gpio_set_level(config.gpio_a, config.aEnabledPinState); - gpio_set_level(config.gpio_b, !config.bEnabledPinState); - break; - - case motorstate_t::REV: - ledc_set_duty(LEDC_HIGH_SPEED_MODE, config.ledc_channel, dutyScaled); - ledc_update_duty(LEDC_HIGH_SPEED_MODE, config.ledc_channel); - //reverse: - gpio_set_level(config.gpio_a, !config.aEnabledPinState); - gpio_set_level(config.gpio_b, config.bEnabledPinState); - break; - } -} diff --git a/board_motorctl/main/motordrivers.hpp b/board_motorctl/main/motordrivers.hpp deleted file mode 100644 index 745cbf3..0000000 --- a/board_motorctl/main/motordrivers.hpp +++ /dev/null @@ -1,65 +0,0 @@ -#pragma once - -extern "C" -{ -#include "freertos/FreeRTOS.h" -#include "freertos/task.h" -#include "driver/gpio.h" -#include "esp_log.h" - -#include "driver/ledc.h" -#include "esp_err.h" -} - -#include - - -//==================================== -//===== single100a motor driver ====== -//==================================== - -//-------------------------------------------- -//---- struct, enum, variable declarations --- -//-------------------------------------------- -//motorstate_t, motorstateStr outsourced to common/types.hpp -#include "types.hpp" - -//struct with all config parameters for single100a motor driver -typedef struct single100a_config_t { - gpio_num_t gpio_pwm; - gpio_num_t gpio_a; - gpio_num_t gpio_b; - gpio_num_t gpio_brakeRelay; - ledc_timer_t ledc_timer; - ledc_channel_t ledc_channel; - bool aEnabledPinState; - bool bEnabledPinState; - ledc_timer_bit_t resolution; - int pwmFreq; -} single100a_config_t; - - - -//-------------------------------- -//------- single100a class ------- -//-------------------------------- -class single100a { - public: - //--- constructor --- - single100a(single100a_config_t config_f); //provide config struct (see above) - - //--- functions --- - void set(motorstate_t state, float duty_f = 0); //set mode and duty of the motor (see motorstate_t above) - //TODO: add functions to get the current state and duty - - private: - //--- functions --- - void init(); //initialize pwm and gpio outputs, calculate maxDuty - - //--- variables --- - single100a_config_t config; - uint32_t dutyMax; - motorstate_t state = motorstate_t::IDLE; - bool brakeWaitingForRelay = false; - uint32_t timestamp_brakeRelayPowered; -}; diff --git a/board_single/CMakeLists.txt b/board_single/CMakeLists.txt new file mode 100644 index 0000000..e827903 --- /dev/null +++ b/board_single/CMakeLists.txt @@ -0,0 +1,9 @@ +# For more information about build system see +# https://docs.espressif.com/projects/esp-idf/en/latest/api-guides/build-system.html +# The following five lines of boilerplate have to be in your project's +# CMakeLists in this exact order for cmake to work correctly +cmake_minimum_required(VERSION 3.5) + +include($ENV{IDF_PATH}/tools/cmake/project.cmake) +set(EXTRA_COMPONENT_DIRS "../components ../common") +project(armchair-singleBoard) diff --git a/board_single/dependencies.lock b/board_single/dependencies.lock new file mode 100644 index 0000000..7a46da1 --- /dev/null +++ b/board_single/dependencies.lock @@ -0,0 +1,9 @@ +dependencies: + idf: + component_hash: null + source: + type: idf + version: 4.4.4 +manifest_hash: dcf4d39b94252de130019eadceb989d72b0dbc26b552cfdcbb50f6da531d2b92 +target: esp32 +version: 1.0.0 diff --git a/board_single/main/CMakeLists.txt b/board_single/main/CMakeLists.txt new file mode 100644 index 0000000..d0ac056 --- /dev/null +++ b/board_single/main/CMakeLists.txt @@ -0,0 +1,14 @@ +idf_component_register( + SRCS + "main.cpp" + "config.cpp" + "control.cpp" + "button.cpp" + "fan.cpp" + "auto.cpp" + "display.cpp" + INCLUDE_DIRS + "." + ) + +spiffs_create_partition_image(spiffs ../../react-app/build FLASH_IN_PROJECT) diff --git a/board_single/main/auto.cpp b/board_single/main/auto.cpp new file mode 100644 index 0000000..4cf4a71 --- /dev/null +++ b/board_single/main/auto.cpp @@ -0,0 +1,88 @@ +#include "auto.hpp" +#include "config.hpp" + +//tag for logging +static const char * TAG = "automatedArmchair"; + + +//============================= +//======== constructor ======== +//============================= +automatedArmchair::automatedArmchair(void) { + //create command queue + commandQueue = xQueueCreate( 32, sizeof( commandSimple_t ) ); //TODO add max size to config? +} + + + +//============================== +//====== generateCommands ====== +//============================== +motorCommands_t automatedArmchair::generateCommands(auto_instruction_t * instruction) { + //reset instruction + *instruction = auto_instruction_t::NONE; + //check if previous command is finished + if ( esp_log_timestamp() > timestampCmdFinished ) { + //get next command from queue + if( xQueueReceive( commandQueue, &cmdCurrent, pdMS_TO_TICKS(500) ) ) { + ESP_LOGI(TAG, "running next command from queue..."); + //copy instruction to be provided to control task + *instruction = cmdCurrent.instruction; + //set acceleration / fading parameters according to command + motorLeft.setFade(fadeType_t::DECEL, cmdCurrent.fadeDecel); + motorRight.setFade(fadeType_t::DECEL, cmdCurrent.fadeDecel); + motorLeft.setFade(fadeType_t::ACCEL, cmdCurrent.fadeAccel); + motorRight.setFade(fadeType_t::ACCEL, cmdCurrent.fadeAccel); + //calculate timestamp the command is finished + timestampCmdFinished = esp_log_timestamp() + cmdCurrent.msDuration; + //copy the new commands + motorCommands = cmdCurrent.motorCmds; + } else { //queue empty + ESP_LOGD(TAG, "no new command in queue -> set motors to IDLE"); + motorCommands = motorCmds_bothMotorsIdle; + } + } else { //previous command still running + ESP_LOGD(TAG, "command still running -> no change"); + } + + //TODO also return instructions via call by reference + return motorCommands; +} + + + +//============================ +//======== addCommand ======== +//============================ +//function that adds a basic command to the queue +void automatedArmchair::addCommand(commandSimple_t command) { + //add command to queue + if ( xQueueSend( commandQueue, ( void * )&command, ( TickType_t ) 0 ) ){ + ESP_LOGI(TAG, "Successfully inserted command to queue"); + } else { + ESP_LOGE(TAG, "Failed to insert new command to queue"); + } +} + +void automatedArmchair::addCommands(commandSimple_t commands[], size_t count) { + for (int i = 0; i < count; i++) { + ESP_LOGI(TAG, "Reading command no. %d from provided array", i); + addCommand(commands[i]); + } +} + + +//=============================== +//======== clearCommands ======== +//=============================== +//function that deletes all pending/queued commands +//e.g. when switching modes +motorCommands_t automatedArmchair::clearCommands() { + //clear command queue + xQueueReset( commandQueue ); + ESP_LOGW(TAG, "command queue was successfully emptied"); + //return commands for idling both motors + motorCommands = motorCmds_bothMotorsIdle; + return motorCmds_bothMotorsIdle; +} + diff --git a/board_single/main/auto.hpp b/board_single/main/auto.hpp new file mode 100644 index 0000000..8b799fb --- /dev/null +++ b/board_single/main/auto.hpp @@ -0,0 +1,87 @@ +#pragma once + +extern "C" +{ +#include "freertos/FreeRTOS.h" +#include "freertos/task.h" +#include "esp_log.h" +#include "esp_err.h" +} + +#include "freertos/queue.h" +#include +#include "motorctl.hpp" + + + +//-------------------------------------------- +//---- struct, enum, variable declarations --- +//-------------------------------------------- +//enum for special instructions / commands to be run in control task +enum class auto_instruction_t { NONE, SWITCH_PREV_MODE, SWITCH_JOYSTICK_MODE, RESET_ACCEL_DECEL, RESET_ACCEL, RESET_DECEL }; + +//struct for a simple command +//e.g. put motors in a certain state for certain time +typedef struct commandSimple_t{ + motorCommands_t motorCmds; + uint32_t msDuration; + uint32_t fadeDecel; + uint32_t fadeAccel; + auto_instruction_t instruction; +} commandSimple_t; + + + +//------------------------------------ +//----- automatedArmchair class ----- +//------------------------------------ +class automatedArmchair { + public: + //--- methods --- + //constructor + automatedArmchair(void); + //function to generate motor commands + //can be also seen as handle function + //TODO: go with other approach: separate task for handling auto mode + // - receive commands with queue anyways + // - => use delay function + // - have a queue that outputs current motor state/commands -> repeatedly check the queue in control task + //function that handles automatic driving and returns motor commands + //also provides instructions to be executed in control task via pointer + motorCommands_t generateCommands(auto_instruction_t * instruction); + + //function that adds a basic command to the queue + void addCommand(commandSimple_t command); + //function that adds an array of basic commands to queue + void addCommands(commandSimple_t commands[], size_t count); + + //function that deletes all pending/queued commands + motorCommands_t clearCommands(); + + + private: + //--- methods --- + //--- objects --- + //TODO: add buzzer here + //--- variables --- + //queue for storing pending commands + QueueHandle_t commandQueue = NULL; + //current running command + commandSimple_t cmdCurrent; + //timestamp current command is finished + uint32_t timestampCmdFinished = 0; + + motorCommands_t motorCommands; + + //command preset for idling motors + const motorCommand_t motorCmd_motorIdle = { + .state = motorstate_t::IDLE, + .duty = 0 + }; + const motorCommands_t motorCmds_bothMotorsIdle = { + .left = motorCmd_motorIdle, + .right = motorCmd_motorIdle + }; +}; + + diff --git a/board_single/main/button.cpp b/board_single/main/button.cpp new file mode 100644 index 0000000..0974fdc --- /dev/null +++ b/board_single/main/button.cpp @@ -0,0 +1,220 @@ +extern "C" +{ +#include +#include +#include +#include "freertos/FreeRTOS.h" +#include "esp_log.h" +} + +#include "button.hpp" + + + +//tag for logging +static const char * TAG = "button"; + + + +//----------------------------- +//-------- constructor -------- +//----------------------------- +buttonCommands::buttonCommands(gpio_evaluatedSwitch * button_f, evaluatedJoystick * joystick_f, controlledArmchair * control_f, buzzer_t * buzzer_f, controlledMotor * motorLeft_f, controlledMotor * motorRight_f){ + //copy object pointers + button = button_f; + joystick = joystick_f; + control = control_f; + buzzer = buzzer_f; + motorLeft = motorLeft_f; + motorRight = motorRight_f; + //TODO declare / configure evaluatedSwitch here instead of config (unnecessary that button object is globally available - only used here)? +} + + + +//---------------------------- +//--------- action ----------- +//---------------------------- +//function that runs commands depending on a count value +void buttonCommands::action (uint8_t count, bool lastPressLong){ + //--- variable declarations --- + bool decelEnabled; //for different beeping when toggling + commandSimple_t cmds[8]; //array for commands for automatedArmchair + + //--- get joystick position --- + //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; + + 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){ + //define commands + cmds[0] = + { + .motorCmds = { + .left = {motorstate_t::REV, 90}, + .right = {motorstate_t::REV, 90} + }, + .msDuration = 1200, + .fadeDecel = 800, + .fadeAccel = 1300, + .instruction = auto_instruction_t::NONE + }; + cmds[1] = + { + .motorCmds = { + .left = {motorstate_t::FWD, 70}, + .right = {motorstate_t::FWD, 70} + }, + .msDuration = 70, + .fadeDecel = 0, + .fadeAccel = 300, + .instruction = auto_instruction_t::NONE + }; + cmds[2] = + { + .motorCmds = { + .left = {motorstate_t::IDLE, 0}, + .right = {motorstate_t::IDLE, 0} + }, + .msDuration = 10, + .fadeDecel = 800, + .fadeAccel = 1300, + .instruction = auto_instruction_t::SWITCH_JOYSTICK_MODE + }; + + //send commands to automatedArmchair command queue + armchair.addCommands(cmds, 3); + + //change mode to AUTO + control->changeMode(controlMode_t::AUTO); + return; + } + + //toggle idle when 2x pressed + ESP_LOGW(TAG, "cmd %d: toggle IDLE", count); + control->toggleIdle(); //toggle between idle and previous/default mode + break; + + + case 3: + ESP_LOGW(TAG, "cmd %d: switch to JOYSTICK", count); + control->changeMode(controlMode_t::JOYSTICK); //switch to JOYSTICK mode + break; + + case 4: + 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: + 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 deceleration fading between on and off + //decelEnabled = motorLeft->toggleFade(fadeType_t::DECEL); + //motorRight->toggleFade(fadeType_t::DECEL); + decelEnabled = motorLeft->toggleFade(fadeType_t::ACCEL); + motorRight->toggleFade(fadeType_t::ACCEL); + ESP_LOGW(TAG, "cmd %d: toggle deceleration fading to: %d", count, (int)decelEnabled); + if (decelEnabled){ + buzzer->beep(3, 60, 50); + } else { + buzzer->beep(1, 1000, 1); + } + 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)? + break; + + } +} + + + + +//----------------------------- +//------ 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() { + + 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; + } + } +} + + + + diff --git a/board_single/main/button.hpp b/board_single/main/button.hpp new file mode 100644 index 0000000..09de729 --- /dev/null +++ b/board_single/main/button.hpp @@ -0,0 +1,53 @@ +#pragma once + +#include "gpio_evaluateSwitch.hpp" +#include "buzzer.hpp" +#include "control.hpp" +#include "motorctl.hpp" +#include "auto.hpp" +#include "config.hpp" +#include "joystick.hpp" + + + +//=================================== +//====== buttonCommands class ======= +//=================================== +//class which runs commands depending on the count a button was pressed +class buttonCommands { + public: + //--- constructor --- + buttonCommands ( + gpio_evaluatedSwitch * button_f, + evaluatedJoystick * joystick_f, + controlledArmchair * control_f, + buzzer_t * buzzer_f, + controlledMotor * motorLeft_f, + controlledMotor * motorRight_f + ); + + //--- functions --- + //the following function has to be started once in a separate task. + //repeatedly evaluates and processes button events then takes the corresponding action + void startHandleLoop(); + + private: + //--- functions --- + void action(uint8_t count, bool lastPressLong); + + //--- objects --- + gpio_evaluatedSwitch* button; + evaluatedJoystick* joystick; + controlledArmchair * control; + buzzer_t* buzzer; + controlledMotor * motorLeft; + controlledMotor * motorRight; + + //--- variables --- + uint8_t count = 0; + uint32_t timestamp_lastAction = 0; + enum class inputState_t {IDLE, WAIT_FOR_INPUT}; + inputState_t state = inputState_t::IDLE; + +}; + diff --git a/board_single/main/config.cpp b/board_single/main/config.cpp new file mode 100644 index 0000000..7de9113 --- /dev/null +++ b/board_single/main/config.cpp @@ -0,0 +1,199 @@ +#include "config.hpp" + +//=================================== +//======= motor configuration ======= +//=================================== +/* ==> currently using other driver +//--- configure left motor (hardware) --- +single100a_config_t configDriverLeft = { + .gpio_pwm = GPIO_NUM_26, + .gpio_a = GPIO_NUM_16, + .gpio_b = GPIO_NUM_4, + .ledc_timer = LEDC_TIMER_0, + .ledc_channel = LEDC_CHANNEL_0, + .aEnabledPinState = false, //-> pins inverted (mosfets) + .bEnabledPinState = false, + .resolution = LEDC_TIMER_11_BIT, + .pwmFreq = 10000 +}; + +//--- configure right motor (hardware) --- +single100a_config_t configDriverRight = { + .gpio_pwm = GPIO_NUM_27, + .gpio_a = GPIO_NUM_2, + .gpio_b = GPIO_NUM_14, + .ledc_timer = LEDC_TIMER_1, + .ledc_channel = LEDC_CHANNEL_1, + .aEnabledPinState = false, //-> pin inverted (mosfet) + .bEnabledPinState = true, //-> not inverted (direct) + .resolution = LEDC_TIMER_11_BIT, + .pwmFreq = 10000 + }; + */ + +//--- configure sabertooth driver --- (controls both motors in one instance) +sabertooth2x60_config_t sabertoothConfig = { + .gpio_TX = GPIO_NUM_25, + .uart_num = UART_NUM_2 +}; + + +//TODO add motor name string -> then use as log tag? +//--- configure left motor (contol) --- +motorctl_config_t configMotorControlLeft = { + .msFadeAccel = 1800, //acceleration of the motor (ms it takes from 0% to 100%) + .msFadeDecel = 1900, //deceleration of the motor (ms it takes from 100% to 0%) + .currentLimitEnabled = false, + .currentSensor_adc = ADC1_CHANNEL_4, //GPIO32 + .currentSensor_ratedCurrent = 50, + .currentMax = 30, + .deadTimeMs = 0 //minimum time motor is off between direction change +}; + +//--- configure right motor (contol) --- +motorctl_config_t configMotorControlRight = { + .msFadeAccel = 1800, //acceleration of the motor (ms it takes from 0% to 100%) + .msFadeDecel = 1900, //deceleration of the motor (ms it takes from 100% to 0%) + .currentLimitEnabled = false, + .currentSensor_adc = ADC1_CHANNEL_5, //GPIO33 + .currentSensor_ratedCurrent = 50, + .currentMax = 30, + .deadTimeMs = 0 //minimum time motor is off between direction change +}; + + + +//============================== +//======= control config ======= +//============================== +control_config_t configControl = { + .defaultMode = controlMode_t::JOYSTICK, //default mode after startup and toggling IDLE + //--- timeout --- + .timeoutMs = 3*60*1000, //time of inactivity after which the mode gets switched to IDLE + .timeoutTolerancePer = 5, //percentage the duty can vary between timeout checks considered still inactive + //--- http mode --- + +}; + + + +//=============================== +//===== httpJoystick config ===== +//=============================== +httpJoystick_config_t configHttpJoystickMain{ + .toleranceZeroX_Per = 1, //percentage around joystick axis the coordinate snaps to 0 + .toleranceZeroY_Per = 6, + .toleranceEndPer = 2, //percentage before joystick end the coordinate snaps to 1/-1 + .timeoutMs = 2500 //time no new data was received before the motors get turned off +}; + + + +//====================================== +//======= joystick configuration ======= +//====================================== +joystick_config_t configJoystick = { + .adc_x = ADC1_CHANNEL_0, //GPIO36 + .adc_y = ADC1_CHANNEL_3, //GPIO39 + //percentage of joystick range the coordinate of the axis snaps to 0 (0-100) + .tolerance_zeroX_per = 7, //6 + .tolerance_zeroY_per = 10, //7 + //percentage of joystick range the coordinate snaps to -1 or 1 before configured "_max" or "_min" threshold (mechanical end) is reached (0-100) + .tolerance_end_per = 4, + //threshold the radius jumps to 1 before the stick is at max radius (range 0-1) + .tolerance_radius = 0.09, + + //min and max adc values of each axis, !!!AFTER INVERSION!!! is applied: + .x_min = 1710, //=> x=-1 + .x_max = 2980, //=> x=1 + .y_min = 1700, //=> y=-1 + .y_max = 2970, //=> y=1 + //invert adc measurement + .x_inverted = true, + .y_inverted = true +}; + + + +//============================ +//=== configure fan contol === +//============================ +fan_config_t configCooling = { + .gpio_fan = GPIO_NUM_13, + .dutyThreshold = 40, + .minOnMs = 1500, + .minOffMs = 3000, + .turnOffDelayMs = 5000, +}; + + + + + +//============================================ +//======== speed sensor configuration ======== +//============================================ +speedSensor_config_t speedLeft_config{ + .gpioPin = GPIO_NUM_5, + .degreePerGroup = 360/5, + .tireCircumferenceMeter = 210.0*3.141/1000.0, + .directionInverted = false, + .logName = "speedLeft", +}; + +speedSensor_config_t speedRight_config{ + .gpioPin = GPIO_NUM_14, + .degreePerGroup = 360/12, + .tireCircumferenceMeter = 210.0*3.141/1000.0, + .directionInverted = true, + .logName = "speedRight", +}; + + + +//================================= +//===== create global objects ===== +//================================= +//TODO outsource global variables to e.g. global.cpp and only config options here? +//create sabertooth motor driver instance +sabertooth2x60a sabertoothDriver(sabertoothConfig); + + +//--- controlledMotor --- +//functions for updating the duty via certain/current driver that can then be passed to controlledMotor +//-> makes it possible to easily use different motor drivers +//note: ignoring warning "capture of variable 'sabertoothDriver' with non-automatic storage duration", since sabertoothDriver object does not get destroyed anywhere - no lifetime issue +motorSetCommandFunc_t setLeftFunc = [&sabertoothDriver](motorCommand_t cmd) { + sabertoothDriver.setLeft(cmd); +}; +motorSetCommandFunc_t setRightFunc = [&sabertoothDriver](motorCommand_t cmd) { + sabertoothDriver.setRight(cmd); +}; +//create controlled motor instances (motorctl.hpp) +controlledMotor motorLeft(setLeftFunc, configMotorControlLeft); +controlledMotor motorRight(setRightFunc, configMotorControlRight); + +//create speedsensor instances +speedSensor speedLeft (speedLeft_config); +speedSensor speedRight (speedRight_config); + +//create global joystic instance (joystick.hpp) +evaluatedJoystick joystick(configJoystick); + +//create global evaluated switch instance for button next to joystick +gpio_evaluatedSwitch buttonJoystick(GPIO_NUM_21, true, false); //pullup true, not inverted (switch to GND use pullup of controller) + +//create buzzer object on pin 12 with gap between queued events of 100ms +buzzer_t buzzer(GPIO_NUM_12, 100); + +//create global httpJoystick object (http.hpp) +httpJoystick httpJoystickMain(configHttpJoystickMain); + +//create global control object (control.hpp) +controlledArmchair control(configControl, &buzzer, &motorLeft, &motorRight, &joystick, &httpJoystickMain); + +//create global automatedArmchair object (for auto-mode) (auto.hpp) +automatedArmchair armchair; + + + diff --git a/board_single/main/config.hpp b/board_single/main/config.hpp new file mode 100644 index 0000000..d9b8d1b --- /dev/null +++ b/board_single/main/config.hpp @@ -0,0 +1,51 @@ +#pragma once + +#include "motordrivers.hpp" +#include "motorctl.hpp" +#include "joystick.hpp" + +#include "gpio_evaluateSwitch.hpp" +#include "buzzer.hpp" +#include "control.hpp" +#include "fan.hpp" +#include "http.hpp" +#include "auto.hpp" +#include "speedsensor.hpp" + + +//in IDLE mode: set loglevel for evaluatedJoystick to DEBUG +//and repeatedly read joystick e.g. for manually calibrating / testing joystick +#define JOYSTICK_LOG_IN_IDLE + + +//TODO outsource global variables to e.g. global.cpp and only config options here? + +//create global controlledMotor instances for both motors +extern controlledMotor motorLeft; +extern controlledMotor motorRight; + +//create global joystic instance +extern evaluatedJoystick joystick; + +//create global evaluated switch instance for button next to joystick +extern gpio_evaluatedSwitch buttonJoystick; + +//create global buzzer object +extern buzzer_t buzzer; + +//create global control object +extern controlledArmchair control; + +//create global automatedArmchair object (for auto-mode) +extern automatedArmchair armchair; + +//create global httpJoystick object +//extern httpJoystick httpJoystickMain; + +//configuration for fans / cooling +extern fan_config_t configCooling; + +//create global objects for measuring speed +extern speedSensor speedLeft; +extern speedSensor speedRight; + diff --git a/board_single/main/control.cpp b/board_single/main/control.cpp new file mode 100644 index 0000000..fc9e4e3 --- /dev/null +++ b/board_single/main/control.cpp @@ -0,0 +1,479 @@ +extern "C" +{ +#include +#include "freertos/FreeRTOS.h" +#include "esp_log.h" +#include "freertos/queue.h" + +//custom C libraries +#include "wifi.h" +} + +#include "config.hpp" +#include "control.hpp" + + +//used definitions moved from config.hpp: +//#define JOYSTICK_TEST + + +//tag for logging +static const char * TAG = "control"; +const char* controlModeStr[7] = {"IDLE", "JOYSTICK", "MASSAGE", "HTTP", "MQTT", "BLUETOOTH", "AUTO"}; + + +//----------------------------- +//-------- constructor -------- +//----------------------------- +controlledArmchair::controlledArmchair ( + control_config_t config_f, + buzzer_t * buzzer_f, + controlledMotor* motorLeft_f, + controlledMotor* motorRight_f, + evaluatedJoystick* joystick_f, + httpJoystick* httpJoystick_f + ){ + + //copy configuration + config = config_f; + //copy object pointers + buzzer = buzzer_f; + motorLeft = motorLeft_f; + motorRight = motorRight_f; + joystick_l = joystick_f, + httpJoystickMain_l = httpJoystick_f; + //set default mode from config + modePrevious = config.defaultMode; + + //TODO declare / configure controlled motors here instead of config (unnecessary that button object is globally available - only used here)? +} + + + +//---------------------------------- +//---------- Handle loop ----------- +//---------------------------------- +//function that repeatedly generates motor commands depending on the current mode +//also handles fading and current-limit +void controlledArmchair::startHandleLoop() { + while (1){ + ESP_LOGV(TAG, "control task executing... mode=%s", controlModeStr[(int)mode]); + + switch(mode) { + default: + mode = controlMode_t::IDLE; + break; + + case controlMode_t::IDLE: + //copy preset commands for idling both motors + commands = cmds_bothMotorsIdle; + motorRight->setTarget(commands.right.state, commands.right.duty); + motorLeft->setTarget(commands.left.state, commands.left.duty); + vTaskDelay(200 / portTICK_PERIOD_MS); +#ifdef JOYSTICK_LOG_IN_IDLE + //get joystick data here (without using it) + //since loglevel is DEBUG, calculateion details is output + joystick_l->getData(); //get joystick data here +#endif + break; + + + case controlMode_t::JOYSTICK: + vTaskDelay(20 / portTICK_PERIOD_MS); + //get current joystick data with getData method of evaluatedJoystick + stickData = joystick_l->getData(); + //additionaly scale coordinates (more detail in slower area) + joystick_scaleCoordinatesLinear(&stickData, 0.6, 0.35); //TODO: add scaling parameters to config + //generate motor commands + commands = joystick_generateCommandsDriving(stickData, altStickMapping); + //apply motor commands + motorRight->setTarget(commands.right.state, commands.right.duty); + motorLeft->setTarget(commands.left.state, commands.left.duty); + //TODO make motorctl.setTarget also accept motorcommand struct directly + break; + + + case controlMode_t::MASSAGE: + vTaskDelay(10 / portTICK_PERIOD_MS); + //--- read joystick --- + //only update joystick data when input not frozen + if (!freezeInput){ + stickData = joystick_l->getData(); + } + //--- generate motor commands --- + //pass joystick data from getData method of evaluatedJoystick to generateCommandsShaking function + commands = joystick_generateCommandsShaking(stickData); + //apply motor commands + motorRight->setTarget(commands.right.state, commands.right.duty); + motorLeft->setTarget(commands.left.state, commands.left.duty); + break; + + + case controlMode_t::HTTP: + //--- get joystick data from queue --- + //Note this function waits several seconds (httpconfig.timeoutMs) for data to arrive, otherwise Center data or NULL is returned + //TODO: as described above, when changing modes it might delay a few seconds for the change to apply + stickData = httpJoystickMain_l->getData(); + //scale coordinates additionally (more detail in slower area) + joystick_scaleCoordinatesLinear(&stickData, 0.6, 0.4); //TODO: add scaling parameters to config + ESP_LOGD(TAG, "generating commands from x=%.3f y=%.3f radius=%.3f angle=%.3f", stickData.x, stickData.y, stickData.radius, stickData.angle); + //--- generate motor commands --- + //Note: timeout (no data received) is handled in getData method + commands = joystick_generateCommandsDriving(stickData, altStickMapping); + + //--- apply commands to motors --- + //TODO make motorctl.setTarget also accept motorcommand struct directly + motorRight->setTarget(commands.right.state, commands.right.duty); + motorLeft->setTarget(commands.left.state, commands.left.duty); + break; + + + case controlMode_t::AUTO: + vTaskDelay(20 / portTICK_PERIOD_MS); + //generate commands + commands = armchair.generateCommands(&instruction); + //--- apply commands to motors --- + //TODO make motorctl.setTarget also accept motorcommand struct directly + motorRight->setTarget(commands.right.state, commands.right.duty); + motorLeft->setTarget(commands.left.state, commands.left.duty); + + //process received instruction + switch (instruction) { + case auto_instruction_t::NONE: + break; + case auto_instruction_t::SWITCH_PREV_MODE: + toggleMode(controlMode_t::AUTO); + break; + case auto_instruction_t::SWITCH_JOYSTICK_MODE: + changeMode(controlMode_t::JOYSTICK); + break; + case auto_instruction_t::RESET_ACCEL_DECEL: + //enable downfading (set to default value) + motorLeft->setFade(fadeType_t::DECEL, true); + motorRight->setFade(fadeType_t::DECEL, true); + //set upfading to default value + motorLeft->setFade(fadeType_t::ACCEL, true); + motorRight->setFade(fadeType_t::ACCEL, true); + break; + case auto_instruction_t::RESET_ACCEL: + //set upfading to default value + motorLeft->setFade(fadeType_t::ACCEL, true); + motorRight->setFade(fadeType_t::ACCEL, true); + break; + case auto_instruction_t::RESET_DECEL: + //enable downfading (set to default value) + motorLeft->setFade(fadeType_t::DECEL, true); + motorRight->setFade(fadeType_t::DECEL, true); + break; + } + 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 ------ + //----------------------- + //this section is run about every 5s (+500ms) + if (esp_log_timestamp() - timestamp_SlowLoopLastRun > 5000) { + ESP_LOGV(TAG, "running slow loop... time since last run: %.1fs", (float)(esp_log_timestamp() - timestamp_SlowLoopLastRun)/1000); + timestamp_SlowLoopLastRun = esp_log_timestamp(); + + //run function which detects timeout (switch to idle) + handleTimeout(); + } + + }//end while(1) +}//end startHandleLoop + + + +//----------------------------------- +//---------- resetTimeout ----------- +//----------------------------------- +void controlledArmchair::resetTimeout(){ + //TODO mutex + timestamp_lastActivity = esp_log_timestamp(); +} + + + +//------------------------------------ +//--------- sendButtonEvent ---------- +//------------------------------------ +void controlledArmchair::sendButtonEvent(uint8_t count){ + //TODO mutex - if not replaced with queue + ESP_LOGI(TAG, "setting button event"); + buttonCount = count; +} + + + +//------------------------------------ +//---------- handleTimeout ----------- +//------------------------------------ +//percentage the duty can vary since last timeout check and still counts as incative +//TODO: add this to config +float inactivityTolerance = 10; + +//local function that checks whether two values differ more than a given tolerance +bool validateActivity(float dutyOld, float dutyNow, float tolerance){ + float dutyDelta = dutyNow - dutyOld; + if (fabs(dutyDelta) < tolerance) { + return false; //no significant activity detected + } else { + return true; //there was activity + } +} + +//function that evaluates whether there is no activity/change on the motor duty for a certain time. If so, a switch to IDLE is issued. - has to be run repeatedly in a slow interval +void controlledArmchair::handleTimeout(){ + //check for timeout only when not idling already + if (mode != controlMode_t::IDLE) { + //get current duty from controlled motor objects + float dutyLeftNow = motorLeft->getStatus().duty; + float dutyRightNow = motorRight->getStatus().duty; + + //activity detected on any of the two motors + if (validateActivity(dutyLeft_lastActivity, dutyLeftNow, inactivityTolerance) + || validateActivity(dutyRight_lastActivity, dutyRightNow, inactivityTolerance) + ){ + ESP_LOGD(TAG, "timeout check: [activity] detected since last check -> reset"); + //reset last duty and timestamp + dutyLeft_lastActivity = dutyLeftNow; + dutyRight_lastActivity = dutyRightNow; + resetTimeout(); + } + //no activity on any motor and msTimeout exceeded + else if (esp_log_timestamp() - timestamp_lastActivity > config.timeoutMs){ + ESP_LOGI(TAG, "timeout check: [TIMEOUT], no activity for more than %.ds -> switch to idle", config.timeoutMs/1000); + //toggle to idle mode + toggleIdle(); + } + else { + ESP_LOGD(TAG, "timeout check: [inactive], last activity %.1f s ago, timeout after %d s", (float)(esp_log_timestamp() - timestamp_lastActivity)/1000, config.timeoutMs/1000); + } + } +} + + + +//----------------------------------- +//----------- changeMode ------------ +//----------------------------------- +//function to change to a specified control mode +void controlledArmchair::changeMode(controlMode_t modeNew) { + //reset timeout timer + resetTimeout(); + + //exit if target mode is already active + if (mode == modeNew) { + ESP_LOGE(TAG, "changeMode: Already in target mode '%s' -> nothing to change", controlModeStr[(int)mode]); + return; + } + + //copy previous mode + modePrevious = mode; + + ESP_LOGW(TAG, "=== changing mode from %s to %s ===", controlModeStr[(int)mode], controlModeStr[(int)modeNew]); + + //========== commands change FROM mode ========== + //run functions when changing FROM certain mode + switch(modePrevious){ + default: + ESP_LOGI(TAG, "noting to execute when changing FROM this mode"); + break; + +#ifdef JOYSTICK_LOG_IN_IDLE + case controlMode_t::IDLE: + ESP_LOGI(TAG, "disabling debug output for 'evaluatedJoystick'"); + esp_log_level_set("evaluatedJoystick", ESP_LOG_WARN); //FIXME: loglevel from config + break; +#endif + + case controlMode_t::HTTP: + ESP_LOGW(TAG, "switching from http mode -> disabling http and wifi"); + //stop http server + ESP_LOGI(TAG, "disabling http server..."); + http_stop_server(); + + //FIXME: make wifi function work here - currently starting wifi at startup (see notes main.cpp) + //stop wifi + //TODO: decide whether ap or client is currently used - which has to be disabled? + //ESP_LOGI(TAG, "deinit wifi..."); + //wifi_deinit_client(); + //wifi_deinit_ap(); + ESP_LOGI(TAG, "done stopping http mode"); + break; + + case controlMode_t::MASSAGE: + ESP_LOGW(TAG, "switching from MASSAGE mode -> restoring fading, reset frozen input"); + //TODO: fix issue when downfading was disabled before switching to massage mode - currently it gets enabled again here... + //enable downfading (set to default value) + motorLeft->setFade(fadeType_t::DECEL, true); + motorRight->setFade(fadeType_t::DECEL, true); + //set upfading to default value + motorLeft->setFade(fadeType_t::ACCEL, true); + motorRight->setFade(fadeType_t::ACCEL, true); + //reset frozen input state + freezeInput = false; + break; + + case controlMode_t::AUTO: + ESP_LOGW(TAG, "switching from AUTO mode -> restoring fading to default"); + //TODO: fix issue when downfading was disabled before switching to auto mode - currently it gets enabled again here... + //enable downfading (set to default value) + motorLeft->setFade(fadeType_t::DECEL, true); + motorRight->setFade(fadeType_t::DECEL, true); + //set upfading to default value + motorLeft->setFade(fadeType_t::ACCEL, true); + motorRight->setFade(fadeType_t::ACCEL, true); + break; + } + + + //========== commands change TO mode ========== + //run functions when changing TO certain mode + switch(modeNew){ + default: + ESP_LOGI(TAG, "noting to execute when changing TO this mode"); + break; + + case controlMode_t::IDLE: + buzzer->beep(1, 1500, 0); +#ifdef JOYSTICK_LOG_IN_IDLE + esp_log_level_set("evaluatedJoystick", ESP_LOG_DEBUG); +#endif + break; + + case controlMode_t::HTTP: + ESP_LOGW(TAG, "switching to http mode -> enabling http and wifi"); + //start wifi + //TODO: decide wether ap or client should be started + ESP_LOGI(TAG, "init wifi..."); + + //FIXME: make wifi function work here - currently starting wifi at startup (see notes main.cpp) + //wifi_init_client(); + //wifi_init_ap(); + + //wait for wifi + //ESP_LOGI(TAG, "waiting for wifi..."); + //vTaskDelay(1000 / portTICK_PERIOD_MS); + + //start http server + ESP_LOGI(TAG, "init http server..."); + http_init_server(); + ESP_LOGI(TAG, "done initializing http mode"); + break; + + case controlMode_t::MASSAGE: + ESP_LOGW(TAG, "switching to MASSAGE mode -> reducing fading"); + uint32_t shake_msFadeAccel = 500; //TODO: move this to config + + //disable downfading (max. deceleration) + motorLeft->setFade(fadeType_t::DECEL, false); + motorRight->setFade(fadeType_t::DECEL, false); + //reduce upfading (increase acceleration) + motorLeft->setFade(fadeType_t::ACCEL, shake_msFadeAccel); + motorRight->setFade(fadeType_t::ACCEL, shake_msFadeAccel); + break; + + } + + //--- update mode to new mode --- + //TODO: add mutex + mode = modeNew; +} + + +//TODO simplify the following 3 functions? can be replaced by one? + +//----------------------------------- +//----------- toggleIdle ------------ +//----------------------------------- +//function to toggle between IDLE and previous active mode +void controlledArmchair::toggleIdle() { + //toggle between IDLE and previous mode + toggleMode(controlMode_t::IDLE); +} + + + +//------------------------------------ +//----------- toggleModes ------------ +//------------------------------------ +//function to toggle between two modes, but prefer first argument if entirely different mode is currently active +void controlledArmchair::toggleModes(controlMode_t modePrimary, controlMode_t modeSecondary) { + //switch to secondary mode when primary is already active + if (mode == modePrimary){ + ESP_LOGW(TAG, "toggleModes: switching from primaryMode %s to secondarMode %s", controlModeStr[(int)mode], controlModeStr[(int)modeSecondary]); + buzzer->beep(2,200,100); + changeMode(modeSecondary); //switch to secondary mode + } + //switch to primary mode when any other mode is active + else { + ESP_LOGW(TAG, "toggleModes: switching from %s to primary mode %s", controlModeStr[(int)mode], controlModeStr[(int)modePrimary]); + buzzer->beep(4,200,100); + changeMode(modePrimary); + } +} + + + +//----------------------------------- +//----------- toggleMode ------------ +//----------------------------------- +//function that toggles between certain mode and previous mode +void controlledArmchair::toggleMode(controlMode_t modePrimary){ + + //switch to previous mode when primary is already active + if (mode == modePrimary){ + ESP_LOGW(TAG, "toggleMode: switching from primaryMode %s to previousMode %s", controlModeStr[(int)mode], controlModeStr[(int)modePrevious]); + //buzzer->beep(2,200,100); + changeMode(modePrevious); //switch to previous mode + } + //switch to primary mode when any other mode is active + else { + ESP_LOGW(TAG, "toggleModes: switching from %s to primary mode %s", controlModeStr[(int)mode], controlModeStr[(int)modePrimary]); + //buzzer->beep(4,200,100); + changeMode(modePrimary); + } +} diff --git a/board_single/main/control.hpp b/board_single/main/control.hpp new file mode 100644 index 0000000..8ed1e66 --- /dev/null +++ b/board_single/main/control.hpp @@ -0,0 +1,130 @@ +#pragma once + +#include "motordrivers.hpp" +#include "motorctl.hpp" +#include "buzzer.hpp" +#include "http.hpp" +#include "auto.hpp" + + +//-------------------------------------------- +//---- struct, enum, variable declarations --- +//-------------------------------------------- +//enum that decides how the motors get controlled +enum class controlMode_t {IDLE, JOYSTICK, MASSAGE, HTTP, MQTT, BLUETOOTH, AUTO}; +//string array representing the mode enum (for printing the state as string) +extern const char* controlModeStr[7]; + +//--- control_config_t --- +//struct with config parameters +typedef struct control_config_t { + controlMode_t defaultMode; //default mode after startup and toggling IDLE + //timeout options + uint32_t timeoutMs; //time of inactivity after which the mode gets switched to IDLE + float timeoutTolerancePer; //percentage the duty can vary between timeout checks considered still inactive +} control_config_t; + + + + +//================================== +//========= control class ========== +//================================== +//controls the mode the armchair operates +//repeatedly generates the motor commands corresponding to current mode and sends those to motorcontrol +class controlledArmchair { + public: + //--- constructor --- + controlledArmchair ( + control_config_t config_f, + buzzer_t* buzzer_f, + controlledMotor* motorLeft_f, + controlledMotor* motorRight_f, + evaluatedJoystick* joystick_f, + httpJoystick* httpJoystick_f + ); + + //--- functions --- + //task that repeatedly generates motor commands depending on the current mode + void startHandleLoop(); + + //function that changes to a specified control mode + void changeMode(controlMode_t modeNew); + + //function that toggle between IDLE and previous active mode (or default if not switched to certain mode yet) + void toggleIdle(); + + //function that toggles between two modes, but prefers first argument if entirely different mode is currently active + void toggleModes(controlMode_t modePrimary, controlMode_t modeSecondary); + + //toggle between certain mode and previous mode + void toggleMode(controlMode_t modePrimary); + + //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); + + private: + + //--- functions --- + //function that evaluates whether there is no activity/change on the motor duty for a certain time, if so a switch to IDLE is issued. - has to be run repeatedly in a slow interval + void handleTimeout(); + + //--- objects --- + buzzer_t* buzzer; + controlledMotor* motorLeft; + controlledMotor* motorRight; + httpJoystick* httpJoystickMain_l; + evaluatedJoystick* joystick_l; + + //---variables --- + //struct for motor commands returned by generate functions of each mode + motorCommands_t commands; + //struct with config parameters + control_config_t config; + + //store joystick data + joystickData_t stickData; + bool altStickMapping; //alternative joystick mapping (reverse mapped differently) + + //variables for http mode + uint32_t http_timestamp_lastData = 0; + + //variables for MASSAGE mode + bool freezeInput = false; + + //variables for AUTO mode + auto_instruction_t instruction = auto_instruction_t::NONE; //variable to receive instructions from automatedArmchair + + //variable to store button event + uint8_t buttonCount = 0; + + //definition of mode enum + controlMode_t mode = controlMode_t::IDLE; + + //variable to store mode when toggling IDLE mode + controlMode_t modePrevious; //default mode + + //command preset for idling motors + const motorCommand_t cmd_motorIdle = { + .state = motorstate_t::IDLE, + .duty = 0 + }; + const motorCommands_t cmds_bothMotorsIdle = { + .left = cmd_motorIdle, + .right = cmd_motorIdle + }; + + //variable for slow loop + uint32_t timestamp_SlowLoopLastRun = 0; + + //variables for detecting timeout (switch to idle, after inactivity) + float dutyLeft_lastActivity = 0; + float dutyRight_lastActivity = 0; + uint32_t timestamp_lastActivity = 0; +}; + + diff --git a/board_single/main/display.cpp b/board_single/main/display.cpp new file mode 100644 index 0000000..cfabf74 --- /dev/null +++ b/board_single/main/display.cpp @@ -0,0 +1,323 @@ +#include "display.hpp" +extern "C"{ +#include +} + + +//# +//# SSD1306 Configuration +//# +#define GPIO_RANGE_MAX 33 +#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 ADC_BATT_VOLTAGE ADC1_CHANNEL_6 +#define BAT_CELL_COUNT 7 + + + + + +//-------------------------- +//------- getVoltage ------- +//-------------------------- +//TODO duplicate code: getVoltage also defined in currentsensor.cpp -> outsource this +//local function to get average voltage from adc +float getVoltage1(adc1_channel_t adc, uint32_t samples){ + //measure voltage + int measure = 0; + for (int j=0; jchargePercent values +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 cellVoltage = voltage/BAT_CELL_COUNT; + int size = sizeof(voltageLevels) / sizeof(voltageLevels[0]); + int sizePer = sizeof(percentageLevels) / sizeof(percentageLevels[0]); + //check if configured correctly + if (size != sizePer) { + ESP_LOGE(TAG, "getBatteryPercent - count of configured percentages do not match count of voltages"); + return 0; + } + if (cellVoltage <= voltageLevels[0]) { + return 0.0; + } else if (cellVoltage >= voltageLevels[size - 1]) { + return 100.0; + } + + //scale voltage linear to percent in matched range + for (int i = 1; i < size; ++i) { + if (cellVoltage <= voltageLevels[i]) { + float voltageRange = voltageLevels[i] - voltageLevels[i - 1]; + float voltageOffset = cellVoltage - voltageLevels[i - 1]; + float percentageRange = percentageLevels[i] - percentageLevels[i - 1]; + float percentageOffset = percentageLevels[i - 1]; + float percent = percentageOffset + (voltageOffset / voltageRange) * percentageRange; + ESP_LOGD(TAG, "getBatPercent - cellVoltage=%.3f => percentage=%.3f", cellVoltage, percent); + ESP_LOGD(TAG, "getBatPercent - matched range: %.2fV-%.2fV => %.1f%%-%.1f%%", voltageLevels[i-1], voltageLevels[i], percentageLevels[i-1], percentageLevels[i]); + return percent; + } + } + ESP_LOGE(TAG, "getBatteryPercent - unknown voltage range"); + return 0.0; //unknown range +} + +float getBatteryPercent(){ + float voltage = getBatteryVoltage(); + return getBatteryPercent(voltage); +} + + + + +//============================ +//======= 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; + + display_init(); + //TODO check if successfully initialized + + //welcome msg + strcpy(buf, "Hello"); + ssd1306_display_text_x3(&dev, 0, buf, 5, false); + vTaskDelay(1000 / portTICK_PERIOD_MS); + + //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); + } + + //---- 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++; + } + //TODO add pages and menus + + + + //----------------------------------- + //---- text-related example code ---- + //----------------------------------- + //ssd1306_display_text(&dev, 0, "SSD1306 128x64", 14, false); + //ssd1306_display_text(&dev, 1, "ABCDEFGHIJKLMNOP", 16, false); + //ssd1306_display_text(&dev, 2, "abcdefghijklmnop",16, false); + //ssd1306_display_text(&dev, 3, "Hello World!!", 13, false); + ////ssd1306_clear_line(&dev, 4, true); + ////ssd1306_clear_line(&dev, 5, true); + ////ssd1306_clear_line(&dev, 6, true); + ////ssd1306_clear_line(&dev, 7, true); + //ssd1306_display_text(&dev, 4, "SSD1306 128x64", 14, true); + //ssd1306_display_text(&dev, 5, "ABCDEFGHIJKLMNOP", 16, true); + //ssd1306_display_text(&dev, 6, "abcdefghijklmnop",16, true); + //ssd1306_display_text(&dev, 7, "Hello World!!", 13, true); + // + //// Display Count Down + //uint8_t image[24]; + //memset(image, 0, sizeof(image)); + //ssd1306_display_image(&dev, top, (6*8-1), image, sizeof(image)); + //ssd1306_display_image(&dev, top+1, (6*8-1), image, sizeof(image)); + //ssd1306_display_image(&dev, top+2, (6*8-1), image, sizeof(image)); + //for(int font=0x39;font>0x30;font--) { + // memset(image, 0, sizeof(image)); + // ssd1306_display_image(&dev, top+1, (7*8-1), image, 8); + // memcpy(image, font8x8_basic_tr[font], 8); + // if (dev._flip) ssd1306_flip(image, 8); + // ssd1306_display_image(&dev, top+1, (7*8-1), image, 8); + // vTaskDelay(1000 / portTICK_PERIOD_MS); + //} + // + //// Scroll Up + //ssd1306_clear_screen(&dev, false); + //ssd1306_contrast(&dev, 0xff); + //ssd1306_display_text(&dev, 0, "---Scroll UP---", 16, true); + ////ssd1306_software_scroll(&dev, 7, 1); + //ssd1306_software_scroll(&dev, (dev._pages - 1), 1); + //for (int line=0;line0;contrast=contrast-0x20) { + ssd1306_contrast(&dev, contrast); + vTaskDelay(40); + } +#endif + +} + diff --git a/board_single/main/display.hpp b/board_single/main/display.hpp new file mode 100644 index 0000000..98c8b79 --- /dev/null +++ b/board_single/main/display.hpp @@ -0,0 +1,18 @@ +extern "C" { +#include +#include +#include +#include "freertos/FreeRTOS.h" +#include "freertos/task.h" +#include "esp_log.h" + +#include "ssd1306.h" +#include "font8x8_basic.h" +} + +#include "config.hpp" + + +//task that inititialized the display, displays welcome message +//and releatedly updates the display with certain content +void display_task( void * pvParameters ); diff --git a/board_single/main/fan.cpp b/board_single/main/fan.cpp new file mode 100644 index 0000000..2ff094e --- /dev/null +++ b/board_single/main/fan.cpp @@ -0,0 +1,82 @@ +extern "C" +{ +#include "freertos/FreeRTOS.h" +#include "freertos/task.h" +#include "esp_log.h" +} + +#include "fan.hpp" + + +//tag for logging +static const char * TAG = "fan-control"; + + +//----------------------------- +//-------- constructor -------- +//----------------------------- +controlledFan::controlledFan (fan_config_t config_f, controlledMotor* motor1_f, controlledMotor* motor2_f ){ + //copy config + config = config_f; + //copy pointer to motor objects + motor1 = motor1_f; + motor2 = motor2_f; + //initialize gpio pin + gpio_pad_select_gpio(config.gpio_fan); + gpio_set_direction(config.gpio_fan, GPIO_MODE_OUTPUT); +} + + + +//-------------------------- +//--------- handle --------- +//-------------------------- +void controlledFan::handle(){ + //get current state of the motor (motorctl.cpp) + motor1Status = motor1->getStatus(); + motor2Status = motor2->getStatus(); + + //--- handle duty threshold --- + //update timestamp if any threshold exceeded + if (motor1Status.duty > config.dutyThreshold + || motor2Status.duty > config.dutyThreshold){ //TODO add temperature threshold + if (!needsCooling){ + timestamp_needsCoolingSet = esp_log_timestamp(); + needsCooling = true; + } + timestamp_lastThreshold = esp_log_timestamp(); + } else { + needsCooling = false; + } + + //--- turn off condition --- + if (fanRunning + && !needsCooling //no more cooling required + && (motor1Status.duty == 0) && (motor2Status.duty == 0) //both motors are off + //-> keeps fans running even when lower than threshold already, however turnOffDelay already started TODO: start turn off delay after motor stop only? + && (esp_log_timestamp() - timestamp_lastThreshold) > config.turnOffDelayMs){ //turn off delay passed + fanRunning = false; + gpio_set_level(config.gpio_fan, 0); + timestamp_turnedOff = esp_log_timestamp(); + ESP_LOGI(TAG, "turned fan OFF gpio=%d, minOnMs=%d, WasOnMs=%d", (int)config.gpio_fan, config.minOnMs, esp_log_timestamp()-timestamp_turnedOn); + } + + //--- turn on condition --- + if (!fanRunning + && needsCooling + && ((esp_log_timestamp() - timestamp_turnedOff) > config.minOffMs) //fans off long enough + && ((esp_log_timestamp() - timestamp_needsCoolingSet) > config.minOnMs)){ //motors on long enough + fanRunning = true; + gpio_set_level(config.gpio_fan, 1); + timestamp_turnedOn = esp_log_timestamp(); + ESP_LOGI(TAG, "turned fan ON gpio=%d, minOffMs=%d, WasOffMs=%d", (int)config.gpio_fan, config.minOffMs, esp_log_timestamp()-timestamp_turnedOff); + } + + //TODO Add statemachine for more specific control? Exponential average? + //TODO idea: try other aproach? increment a variable with certain weights e.g. integrate over duty, then turn fans on and decrement the variable again + + ESP_LOGD(TAG, "fanState=%d, duty1=%f, duty2=%f, needsCooling=%d", fanRunning, motor1Status.duty, motor2Status.duty, needsCooling); +} + + + diff --git a/board_single/main/fan.hpp b/board_single/main/fan.hpp new file mode 100644 index 0000000..ca1de2b --- /dev/null +++ b/board_single/main/fan.hpp @@ -0,0 +1,49 @@ +#pragma once + +extern "C" +{ +#include "driver/gpio.h" +} + +#include "motorctl.hpp" + + +//--- fan_config_t --- +//struct with all config parameters for a fan +typedef struct fan_config_t { + gpio_num_t gpio_fan; + float dutyThreshold; + uint32_t minOnMs; + uint32_t minOffMs; + uint32_t turnOffDelayMs; +} fan_config; + + + +//================================== +//====== controlledFan class ======= +//================================== +class controlledFan { + public: + //--- constructor --- + controlledFan (fan_config_t config_f, controlledMotor* motor1_f, controlledMotor* motor2_f ); + + //--- functions --- + void handle(); //has to be run repeatedly in a slow loop + + + private: + //--- variables --- + bool fanRunning = false; + bool needsCooling = false; + uint32_t timestamp_needsCoolingSet; + uint32_t timestamp_lastThreshold = 0; + uint32_t timestamp_turnedOn = 0; + uint32_t timestamp_turnedOff = 0; + fan_config_t config; + controlledMotor * motor1; + controlledMotor * motor2; + + motorCommand_t motor1Status; + motorCommand_t motor2Status; +}; diff --git a/board_single/main/main.cpp b/board_single/main/main.cpp new file mode 100644 index 0000000..21d42e3 --- /dev/null +++ b/board_single/main/main.cpp @@ -0,0 +1,338 @@ +#include "hal/uart_types.h" +#include "motordrivers.hpp" +#include "types.hpp" +extern "C" +{ +#include +#include +#include +#include +#include "freertos/FreeRTOS.h" +#include "freertos/task.h" +#include "driver/gpio.h" +#include "esp_log.h" +#include "sdkconfig.h" +#include "esp_spiffs.h" + +#include "driver/ledc.h" + +//custom C files +#include "wifi.h" +} + +//custom C++ files +#include "config.hpp" +#include "control.hpp" +#include "button.hpp" +#include "http.hpp" + +#include "uart_common.hpp" + +#include "display.hpp" + +//tag for logging +static const char * TAG = "main"; + + + +//==================================== +//========== motorctl task =========== +//==================================== +//task for handling the motors (ramp, current limit, driver) +void task_motorctl( void * pvParameters ){ + ESP_LOGI(TAG, "starting handle loop..."); + while(1){ + motorRight.handle(); + motorLeft.handle(); + //10khz -> T=100us + vTaskDelay(10 / portTICK_PERIOD_MS); + } +} + + + +//====================================== +//============ buzzer task ============= +//====================================== +//TODO: move the task creation to buzzer class (buzzer.cpp) +//e.g. only have function buzzer.createTask() in app_main +void task_buzzer( void * pvParameters ){ + ESP_LOGI("task_buzzer", "Start of buzzer task..."); + //run function that waits for a beep events to arrive in the queue + //and processes them + buzzer.processQueue(); +} + + + +//======================================= +//============ control task ============= +//======================================= +//task that controls the armchair modes and initiates commands generation and applies them to driver +void task_control( void * pvParameters ){ + ESP_LOGI(TAG, "Initializing controlledArmchair and starting handle loop"); + //start handle loop (control object declared in config.hpp) + control.startHandleLoop(); +} + + + +//====================================== +//============ button task ============= +//====================================== +//task that handles the button interface/commands +void task_button( void * pvParameters ){ + ESP_LOGI(TAG, "Initializing command-button and starting handle loop"); + //create button instance + buttonCommands commandButton(&buttonJoystick, &joystick, &control, &buzzer, &motorLeft, &motorRight); + //start handle loop + commandButton.startHandleLoop(); +} + + + +//======================================= +//============== fan task =============== +//======================================= +//task that controlls fans for cooling the drivers +void task_fans( void * pvParameters ){ + ESP_LOGI(TAG, "Initializing fans and starting fan handle loop"); + //create fan instances with config defined in config.cpp + controlledFan fan(configCooling, &motorLeft, &motorRight); + //repeatedly run fan handle function in a slow loop + while(1){ + fan.handle(); + vTaskDelay(500 / portTICK_PERIOD_MS); + } +} + + + +//================================= +//========== init spiffs ========== +//================================= +//initialize spi flash filesystem (used for webserver) +void init_spiffs(){ + ESP_LOGI(TAG, "init spiffs"); + esp_vfs_spiffs_conf_t esp_vfs_spiffs_conf = { + .base_path = "/spiffs", + .partition_label = NULL, + .max_files = 5, + .format_if_mount_failed = true}; + esp_vfs_spiffs_register(&esp_vfs_spiffs_conf); + + size_t total = 0; + size_t used = 0; + esp_spiffs_info(NULL, &total, &used); + + ESP_LOGI(TAG, "SPIFFS: total %d, used %d", total, used); + esp_vfs_spiffs_unregister(NULL); +} + + + +//================================== +//======== define loglevels ======== +//================================== +void setLoglevels(void){ + //set loglevel for all tags: + esp_log_level_set("*", ESP_LOG_WARN); + + //--- set loglevel for individual tags --- + esp_log_level_set("main", ESP_LOG_INFO); + esp_log_level_set("buzzer", ESP_LOG_ERROR); + //esp_log_level_set("motordriver", ESP_LOG_ERROR); + //esp_log_level_set("motor-control", ESP_LOG_INFO); + //esp_log_level_set("evaluatedJoystick", ESP_LOG_DEBUG); + //esp_log_level_set("joystickCommands", ESP_LOG_DEBUG); + esp_log_level_set("button", ESP_LOG_INFO); + esp_log_level_set("control", ESP_LOG_INFO); + esp_log_level_set("fan-control", ESP_LOG_INFO); + esp_log_level_set("wifi", ESP_LOG_INFO); + esp_log_level_set("http", ESP_LOG_INFO); + esp_log_level_set("automatedArmchair", ESP_LOG_DEBUG); + esp_log_level_set("display", ESP_LOG_DEBUG); + //esp_log_level_set("current-sensors", ESP_LOG_INFO); +} + + +//send byte via uart to test sabertooth driver +void sendByte(char data){ + uart_write_bytes(UART_NUM_1, &data, 1); + ESP_LOGI(TAG, "sent %x / %d via uart", data, data); +} + + +//================================= +//=========== app_main ============ +//================================= +extern "C" void app_main(void) { + //enable 5V volate regulator + ESP_LOGW(TAG, "enabling 5V regulator..."); + gpio_pad_select_gpio(GPIO_NUM_17); + gpio_set_direction(GPIO_NUM_17, GPIO_MODE_OUTPUT); + gpio_set_level(GPIO_NUM_17, 1); + + //---- define log levels ---- + setLoglevels(); + + //---------------------------------------------- + //--- create task for controlling the motors --- + //---------------------------------------------- + //task that receives commands, handles ramp and current limit and executes commands using the motordriver function + xTaskCreate(&task_motorctl, "task_motor-control", 2*4096, NULL, 6, NULL); + + //------------------------------ + //--- create task for buzzer --- + //------------------------------ + xTaskCreate(&task_buzzer, "task_buzzer", 2048, NULL, 2, NULL); + + //------------------------------- + //--- create task for control --- + //------------------------------- + //task that generates motor commands depending on the current mode and sends those to motorctl task + xTaskCreate(&task_control, "task_control", 4096, NULL, 5, NULL); + + //------------------------------ + //--- create task for button --- + //------------------------------ + //task that evaluates and processes the button input and runs the configured commands + xTaskCreate(&task_button, "task_button", 4096, NULL, 4, NULL); + + //----------------------------------- + //--- create task for fan control --- + //----------------------------------- + //task that evaluates and processes the button input and runs the configured commands + xTaskCreate(&task_fans, "task_fans", 2048, NULL, 1, NULL); + + + //----------------------------------- + //----- create task for display ----- + //----------------------------------- + //task that handles the display + xTaskCreate(&display_task, "display_task", 2048, NULL, 1, NULL); + + + //beep at startup + buzzer.beep(3, 70, 50); + + //--- initialize nvs-flash and netif (needed for wifi) --- + wifi_initNvs_initNetif(); + + //--- initialize spiffs --- + init_spiffs(); + + //--- initialize and start wifi --- + //FIXME: run wifi_init_client or wifi_init_ap as intended from control.cpp when switching state + //currently commented out because of error "assert failed: xQueueSemaphoreTake queue.c:1549 (pxQueue->uxItemSize == 0)" when calling control->changeMode from button.cpp + //when calling control.changeMode(http) from main.cpp it worked without error for some reason? + ESP_LOGI(TAG,"starting wifi..."); + //wifi_init_client(); //connect to existing wifi + wifi_init_ap(); //start access point + ESP_LOGI(TAG,"done starting wifi"); + + + //--- testing http server --- + // wifi_init_client(); //connect to existing wifi + // vTaskDelay(2000 / portTICK_PERIOD_MS); + // ESP_LOGI(TAG, "initializing http server"); + // http_init_server(); + + + //--- testing force http mode after startup --- + //control.changeMode(controlMode_t::HTTP); + + + + //--- main loop --- + //does nothing except for testing things + while(1){ + vTaskDelay(5000 / portTICK_PERIOD_MS); + //test sabertooth driver + // motors.setLeft({motorstate_t::FWD, 70}); + // vTaskDelay(1000 / portTICK_PERIOD_MS); + // motors.setLeft({motorstate_t::IDLE, 0}); + // vTaskDelay(1000 / portTICK_PERIOD_MS); + // motors.setLeft({motorstate_t::REV, 50}); + // vTaskDelay(1000 / portTICK_PERIOD_MS); + // motors.setLeft(-90); + // vTaskDelay(1000 / portTICK_PERIOD_MS); + // motors.setLeft(90); + // vTaskDelay(1000 / portTICK_PERIOD_MS); + // motors.setLeft(0); + // vTaskDelay(1000 / portTICK_PERIOD_MS); + + + //--- test controlledMotor --- (ramp) + // //brake for 1 s + //motorLeft.setTarget(motorstate_t::BRAKE); + //vTaskDelay(1000 / portTICK_PERIOD_MS); + //command 90% - reverse + //motorLeft.setTarget(motorstate_t::REV, 90); + //vTaskDelay(5000 / portTICK_PERIOD_MS); + //motorLeft.setTarget(motorstate_t::FWD, 80); + //vTaskDelay(1000 / portTICK_PERIOD_MS); + //motorLeft.setTarget(motorstate_t::IDLE, 90); + //vTaskDelay(1000 / portTICK_PERIOD_MS); + + + //--------------------------------- + //-------- TESTING section -------- + //--------------------------------- + // //--- test functions at mode change HTTP --- + // control.changeMode(controlMode_t::HTTP); + // vTaskDelay(10000 / portTICK_PERIOD_MS); + // control.changeMode(controlMode_t::IDLE); + // vTaskDelay(10000 / portTICK_PERIOD_MS); + + + //--- test wifi functions --- + // ESP_LOGI(TAG, "creating AP"); + // wifi_init_ap(); //start accesspoint + // vTaskDelay(15000 / portTICK_PERIOD_MS); + // ESP_LOGI(TAG, "stopping wifi"); + // wifi_deinit_ap(); //stop wifi access point + // vTaskDelay(5000 / portTICK_PERIOD_MS); + // ESP_LOGI(TAG, "connecting to wifi"); + // wifi_init_client(); //connect to existing wifi + // vTaskDelay(10000 / portTICK_PERIOD_MS); + // ESP_LOGI(TAG, "stopping wifi"); + // wifi_deinit_client(); //stop wifi client + // vTaskDelay(5000 / portTICK_PERIOD_MS); + + + //--- test button --- + //buttonJoystick.handle(); + // if (buttonJoystick.risingEdge){ + // ESP_LOGI(TAG, "button pressed, was released for %d ms", buttonJoystick.msReleased); + // buzzer.beep(2, 100, 50); + + // }else if (buttonJoystick.fallingEdge){ + // ESP_LOGI(TAG, "button released, was pressed for %d ms", buttonJoystick.msPressed); + // buzzer.beep(1, 200, 0); + // } + + + //--- test joystick commands --- + // motorCommands_t commands = joystick_generateCommandsDriving(joystick); + // motorRight.setTarget(commands.right.state, commands.right.duty); //TODO make motorctl.setTarget also accept motorcommand struct directly + // motorLeft.setTarget(commands.left.state, commands.left.duty); //TODO make motorctl.setTarget also accept motorcommand struct directly + // //motorRight.setTarget(commands.right.state, commands.right.duty); + + + //--- test joystick class --- + //joystickData_t data = joystick.getData(); + //ESP_LOGI(TAG, "position=%s, x=%.1f%%, y=%.1f%%, radius=%.1f%%, angle=%.2f", + // joystickPosStr[(int)data.position], data.x*100, data.y*100, data.radius*100, data.angle); + + //--- test the motor driver --- + //fade up duty - forward + // for (int duty=0; duty<=100; duty+=5) { + // motorLeft.setTarget(motorstate_t::FWD, duty); + // vTaskDelay(100 / portTICK_PERIOD_MS); + // } + + + } + +} diff --git a/board_single/partitions.csv b/board_single/partitions.csv new file mode 100644 index 0000000..7f93f86 --- /dev/null +++ b/board_single/partitions.csv @@ -0,0 +1,6 @@ +# Name, Type, SubType, Offset, Size, Flags +# Note: if you have increased the bootloader size, make sure to update the offsets to avoid overlap +nvs, data, nvs, , 0x6000, +phy_init, data, phy, , 0x1000, +factory, app, factory, , 1M, +spiffs, data, spiffs, , 1M \ No newline at end of file diff --git a/common/CMakeLists.txt b/common/CMakeLists.txt index a49da26..00a73f9 100644 --- a/common/CMakeLists.txt +++ b/common/CMakeLists.txt @@ -4,8 +4,14 @@ idf_component_register( "buzzer.cpp" "uart_common.cpp" "types.cpp" + "motordrivers.cpp" + "motorctl.cpp" + "currentsensor.cpp" + "joystick.cpp" + "http.cpp" + "speedsensor.cpp" INCLUDE_DIRS "." - PRIV_REQUIRES nvs_flash + PRIV_REQUIRES nvs_flash mdns json spiffs esp_http_server ) diff --git a/board_motorctl/main/currentsensor.cpp b/common/currentsensor.cpp similarity index 100% rename from board_motorctl/main/currentsensor.cpp rename to common/currentsensor.cpp diff --git a/board_motorctl/main/currentsensor.hpp b/common/currentsensor.hpp similarity index 100% rename from board_motorctl/main/currentsensor.hpp rename to common/currentsensor.hpp diff --git a/board_control/main/http.cpp b/common/http.cpp similarity index 99% rename from board_control/main/http.cpp rename to common/http.cpp index 04844de..8b784a4 100644 --- a/board_control/main/http.cpp +++ b/common/http.cpp @@ -13,7 +13,7 @@ extern "C" } #include "http.hpp" -#include "config.hpp" +//#include "config.hpp" //tag for logging diff --git a/board_control/main/http.hpp b/common/http.hpp similarity index 93% rename from board_control/main/http.hpp rename to common/http.hpp index 71d4656..0005c84 100644 --- a/board_control/main/http.hpp +++ b/common/http.hpp @@ -68,3 +68,10 @@ class httpJoystick{ .angle = 0 }; }; + + + +//===== global object ===== +//create global instance of httpJoystick +//note: is constructed/configured in config.cpp +extern httpJoystick httpJoystickMain; diff --git a/board_control/main/joystick.cpp b/common/joystick.cpp similarity index 99% rename from board_control/main/joystick.cpp rename to common/joystick.cpp index c282ea6..93d2097 100644 --- a/board_control/main/joystick.cpp +++ b/common/joystick.cpp @@ -310,7 +310,7 @@ motorCommands_t joystick_generateCommandsDriving(joystickData_t data, bool altSt //--- variables --- motorCommands_t commands; - float dutyMax = 90; //TODO add this to config, make changeable during runtime + float dutyMax = 100; //TODO add this to config, make changeable during runtime float dutyOffset = 5; //immediately starts with this duty, TODO add this to config float dutyRange = dutyMax - dutyOffset; diff --git a/board_control/main/joystick.hpp b/common/joystick.hpp similarity index 100% rename from board_control/main/joystick.hpp rename to common/joystick.hpp diff --git a/board_motorctl/main/motorctl.cpp b/common/motorctl.cpp similarity index 94% rename from board_motorctl/main/motorctl.cpp rename to common/motorctl.cpp index b560ad4..1ff8417 100644 --- a/board_motorctl/main/motorctl.cpp +++ b/common/motorctl.cpp @@ -11,11 +11,12 @@ static const char * TAG = "motor-control"; //======== constructor ======== //============================= //constructor, simultaniously initialize instance of motor driver 'motor' and current sensor 'cSensor' with provided config (see below lines after ':') -controlledMotor::controlledMotor(single100a_config_t config_driver, motorctl_config_t config_control): - motor(config_driver), +controlledMotor::controlledMotor(motorSetCommandFunc_t setCommandFunc, motorctl_config_t config_control): cSensor(config_control.currentSensor_adc, config_control.currentSensor_ratedCurrent) { //copy parameters for controlling the motor config = config_control; + //pointer to update motot dury method + motorSetCommand = setCommandFunc; //copy configured default fading durations to actually used variables msFadeAccel = config.msFadeAccel; msFadeDecel = config.msFadeDecel; @@ -80,7 +81,7 @@ void controlledMotor::handle(){ //--- receive commands from queue --- if( xQueueReceive( commandQueue, &commandReceive, ( TickType_t ) 0 ) ) { - ESP_LOGI(TAG, "Read command from queue: state=%s, duty=%.2f", motorstateStr[(int)commandReceive.state], commandReceive.duty); + ESP_LOGD(TAG, "Read command from queue: state=%s, duty=%.2f", motorstateStr[(int)commandReceive.state], commandReceive.duty); state = commandReceive.state; dutyTarget = commandReceive.duty; receiveTimeout = false; @@ -139,7 +140,8 @@ void controlledMotor::handle(){ //brake immediately, update state, duty and exit this cycle of handle function if (state == motorstate_t::BRAKE){ ESP_LOGD(TAG, "braking - skip fading"); - motor.set(motorstate_t::BRAKE, dutyTarget); + motorSetCommand({motorstate_t::BRAKE, dutyTarget}); + ESP_LOGI(TAG, "Set Motordriver: state=%s, duty=%.2f - Measurements: current=%.2f, speed=N/A", motorstateStr[(int)state], dutyNow, currentNow); //dutyNow = 0; return; //no need to run the fade algorithm } @@ -173,8 +175,8 @@ void controlledMotor::handle(){ //----- CURRENT LIMIT ----- + currentNow = cSensor.read(); if ((config.currentLimitEnabled) && (dutyDelta != 0)){ - currentNow = cSensor.read(); if (fabs(currentNow) > config.currentMax){ float dutyOld = dutyNow; //adaptive decrement: @@ -229,7 +231,8 @@ void controlledMotor::handle(){ //--- apply new target to motor --- - motor.set(state, fabs(dutyNow)); + motorSetCommand({state, (float)fabs(dutyNow)}); + ESP_LOGI(TAG, "Set Motordriver: state=%s, duty=%.2f - Measurements: current=%.2f, speed=N/A", motorstateStr[(int)state], dutyNow, currentNow); //note: BRAKE state is handled earlier diff --git a/board_motorctl/main/motorctl.hpp b/common/motorctl.hpp similarity index 86% rename from board_motorctl/main/motorctl.hpp rename to common/motorctl.hpp index 32018be..bea2060 100644 --- a/board_motorctl/main/motorctl.hpp +++ b/common/motorctl.hpp @@ -19,7 +19,7 @@ extern "C" //outsourced to common/types.hpp #include "types.hpp" - +typedef void (*motorSetCommandFunc_t)(motorCommand_t cmd); //=================================== @@ -28,7 +28,7 @@ extern "C" class controlledMotor { public: //--- functions --- - controlledMotor(single100a_config_t config_driver, motorctl_config_t config_control); //constructor with structs for configuring motordriver and parameters for control TODO: add configuration for currentsensor + controlledMotor(motorSetCommandFunc_t setCommandFunc, motorctl_config_t config_control); //constructor with structs for configuring motordriver and parameters for control TODO: add configuration for currentsensor void handle(); //controls motor duty with fade and current limiting feature (has to be run frequently by another task) 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) @@ -44,13 +44,14 @@ class controlledMotor { void init(); //creates currentsensor objects, motordriver objects and queue //--- objects --- - //motor driver - single100a motor; //queue for sending commands to the separate task running the handle() function very fast QueueHandle_t commandQueue = NULL; //current sensor currentSensor cSensor; + //function pointer that sets motor duty (driver) + motorSetCommandFunc_t motorSetCommand; + //--- variables --- //struct for storing control specific parameters motorctl_config_t config; diff --git a/common/motordrivers.cpp b/common/motordrivers.cpp new file mode 100644 index 0000000..4fa581f --- /dev/null +++ b/common/motordrivers.cpp @@ -0,0 +1,320 @@ +#include "motordrivers.hpp" +#include "esp_log.h" +#include "types.hpp" + +//TODO: move from ledc to mcpwm? +//https://docs.espressif.com/projects/esp-idf/en/v4.3/esp32/api-reference/peripherals/mcpwm.html# +//https://github.com/espressif/esp-idf/tree/v4.3/examples/peripherals/mcpwm/mcpwm_basic_config + +//Note fade functionality provided by LEDC would be very useful but unfortunately is not usable here because: +//"Due to hardware limitations, there is no way to stop a fade before it reaches its target duty." + +//tag for logging +static const char * TAG = "motordriver"; + +//ms to wait in IDLE before BRAKE until relay actually switched +#define BRAKE_RELAY_DELAY_MS 300 + + +//==================================== +//===== single100a motor driver ====== +//==================================== + +//----------------------------- +//-------- constructor -------- +//----------------------------- +//copy provided struct with all configuration and run init function +single100a::single100a(single100a_config_t config_f){ + config = config_f; + init(); +} + + + +//---------------------------- +//---------- init ------------ +//---------------------------- +//function to initialize pwm output, gpio pins and calculate maxDuty +void single100a::init(){ + + //--- configure ledc timer --- + ledc_timer_config_t ledc_timer; + ledc_timer.speed_mode = LEDC_HIGH_SPEED_MODE; + ledc_timer.timer_num = config.ledc_timer; + ledc_timer.duty_resolution = config.resolution; //13bit gives max 5khz freq + ledc_timer.freq_hz = config.pwmFreq; + ledc_timer.clk_cfg = LEDC_AUTO_CLK; + //apply configuration + ledc_timer_config(&ledc_timer); + + //--- configure ledc channel --- + ledc_channel_config_t ledc_channel; + ledc_channel.channel = config.ledc_channel; + ledc_channel.duty = 0; + ledc_channel.gpio_num = config.gpio_pwm; + ledc_channel.speed_mode = LEDC_HIGH_SPEED_MODE; + ledc_channel.hpoint = 0; + ledc_channel.timer_sel = config.ledc_timer; + ledc_channel.intr_type = LEDC_INTR_DISABLE; + ledc_channel.flags.output_invert = 0; //TODO: add config option to invert the pwm output? + //apply configuration + ledc_channel_config(&ledc_channel); + + //--- define gpio pins as outputs --- + gpio_pad_select_gpio(config.gpio_a); + gpio_set_direction(config.gpio_a, GPIO_MODE_OUTPUT); + gpio_pad_select_gpio(config.gpio_b); + gpio_set_direction(config.gpio_b, GPIO_MODE_OUTPUT); + gpio_pad_select_gpio(config.gpio_brakeRelay); + gpio_set_direction(config.gpio_brakeRelay, GPIO_MODE_OUTPUT); + + //--- calculate max duty according to selected resolution --- + dutyMax = pow(2, ledc_timer.duty_resolution) -1; + ESP_LOGW(TAG, "initialized single100a driver"); + ESP_LOGW(TAG, "resolution=%dbit, dutyMax value=%d, resolution=%.4f %%", ledc_timer.duty_resolution, dutyMax, 100/(float)dutyMax); +} + + + +//--------------------------- +//----------- set ----------- +//--------------------------- +//function to put the h-bridge module in the desired state and duty cycle +void single100a::set(motorCommand_t cmd){ + set(cmd.state, cmd.duty); +} + +void single100a::set(motorstate_t state_f, float duty_f){ + + //scale provided target duty in percent to available resolution for ledc + uint32_t dutyScaled; + if (duty_f > 100) { //target duty above 100% + dutyScaled = dutyMax; + } else if (duty_f < 0) { //target at or below 0% + state_f = motorstate_t::IDLE; + dutyScaled = 0; + } else { //target duty 0-100% + //scale duty to available resolution + dutyScaled = duty_f / 100 * dutyMax; + } + + ESP_LOGV(TAG, "target-state=%s, duty=%d/%d, duty_input=%.3f%%", motorstateStr[(int)state_f], dutyScaled, dutyMax, duty_f); + + //TODO: only when previous mode was BRAKE? + if (state_f != motorstate_t::BRAKE){ + //reset brake wait state + brakeWaitingForRelay = false; + //turn of brake relay + gpio_set_level(config.gpio_brakeRelay, 0); + } + + //put the single100a h-bridge module in the desired state update duty-cycle + //TODO maybe outsource mode code from once switch case? e.g. idle() brake()... + switch (state_f){ + case motorstate_t::IDLE: + ledc_set_duty(LEDC_HIGH_SPEED_MODE, config.ledc_channel, dutyScaled); + ledc_update_duty(LEDC_HIGH_SPEED_MODE, config.ledc_channel); + //TODO: to fix bugged state of h-bridge module when idle and start again, maybe try to leave pwm signal on for some time before updating a/b pins? + //no brake: (freewheel) + //gpio_set_level(config.gpio_a, config.aEnabledPinState); + //gpio_set_level(config.gpio_b, !config.bEnabledPinState); + gpio_set_level(config.gpio_a, config.aEnabledPinState); + gpio_set_level(config.gpio_b, config.bEnabledPinState); + break; + + case motorstate_t::BRAKE: + //prevent full short (no brake resistors) due to slow relay, also reduces switching load + if (!brakeWaitingForRelay){ + ESP_LOGW(TAG, "BRAKE: turned on relay, waiting in IDLE for %d ms, then apply brake", BRAKE_RELAY_DELAY_MS); + //switch driver to IDLE for now + gpio_set_level(config.gpio_a, config.aEnabledPinState); + gpio_set_level(config.gpio_b, config.bEnabledPinState); + //start brake relay + gpio_set_level(config.gpio_brakeRelay, 1); + timestamp_brakeRelayPowered = esp_log_timestamp(); + brakeWaitingForRelay = true; + } + //check if delay for relay to switch has passed + else if ((esp_log_timestamp() - timestamp_brakeRelayPowered) > BRAKE_RELAY_DELAY_MS) { + ESP_LOGD(TAG, "applying brake with brake-resistors at duty=%.2f%%", duty_f); + //switch driver to BRAKE + gpio_set_level(config.gpio_a, !config.aEnabledPinState); + gpio_set_level(config.gpio_b, !config.bEnabledPinState); + //apply duty + //FIXME switch between BREAK and IDLE with PWM and ignore pwm-pin? (needs test) + ledc_set_duty(LEDC_HIGH_SPEED_MODE, config.ledc_channel, dutyScaled); + ledc_update_duty(LEDC_HIGH_SPEED_MODE, config.ledc_channel); + } else { + //waiting... stay in IDLE + ESP_LOGD(TAG, "waiting for brake relay to close (IDLE)..."); + gpio_set_level(config.gpio_a, config.aEnabledPinState); + gpio_set_level(config.gpio_b, config.bEnabledPinState); + } + break; + + case motorstate_t::FWD: + ledc_set_duty(LEDC_HIGH_SPEED_MODE, config.ledc_channel, dutyScaled); + ledc_update_duty(LEDC_HIGH_SPEED_MODE, config.ledc_channel); + //forward: + gpio_set_level(config.gpio_a, config.aEnabledPinState); + gpio_set_level(config.gpio_b, !config.bEnabledPinState); + break; + + case motorstate_t::REV: + ledc_set_duty(LEDC_HIGH_SPEED_MODE, config.ledc_channel, dutyScaled); + ledc_update_duty(LEDC_HIGH_SPEED_MODE, config.ledc_channel); + //reverse: + gpio_set_level(config.gpio_a, !config.aEnabledPinState); + gpio_set_level(config.gpio_b, config.bEnabledPinState); + break; + } +} + + + + + + +//========================================== +//===== sabertooth 2x60A motor driver ====== +//========================================== + +//----------------------------- +//-------- constructor -------- +//----------------------------- +sabertooth2x60a::sabertooth2x60a(sabertooth2x60_config_t config_f){ + config = config_f; + init(); +} + + +//---------------------------- +//----------- init ----------- +//---------------------------- +void sabertooth2x60a::init(){ + ESP_LOGW(TAG, "initializing uart..."); + uart_config_t uart_config = { + .baud_rate = 9600, //dip switches: 101011 + .data_bits = UART_DATA_8_BITS, + .parity = UART_PARITY_DISABLE, + .stop_bits = UART_STOP_BITS_1, + .flow_ctrl = UART_HW_FLOWCTRL_DISABLE, + }; + ESP_LOGI(TAG, "configure..."); + ESP_ERROR_CHECK(uart_param_config(config.uart_num, &uart_config)); + ESP_LOGI(TAG, "setpins..."); + ESP_ERROR_CHECK(uart_set_pin(config.uart_num, config.gpio_TX, GPIO_NUM_NC, 0, 0)); + ESP_LOGI(TAG, "init..."); + ESP_ERROR_CHECK(uart_driver_install(config.uart_num, 1024, 1024, 10, NULL, 0)); //todo ring buffer less / 0 + uart_isInitialized = true; +} + + + +//---------- motorCommand to signedDuty ---------- +float motorCommandToSignedDuty(motorCommand_t cmd){ + //if (cmd.duty > 100) cmd.duty = 100; + //else if (cmd.duty < 0) cmd.duty = 0; + float duty = 0; + switch (cmd.state){ + case motorstate_t::FWD: + duty = cmd.duty; + break; + case motorstate_t::REV: + duty = - cmd.duty; + break; + case motorstate_t::IDLE: + case motorstate_t::BRAKE: + duty = 0; + break; + } + return duty; +} + + + +//-------- send byte -------- +//send byte via uart to sabertooth driver +void sabertooth2x60a::sendByte(char data){ + //TODO mutex? + if (!uart_isInitialized){ + ESP_LOGE(TAG, "uart not initialized, not sending command %d...", data); + return; + } + uart_write_bytes(config.uart_num, &data, 1); + ESP_LOGD(TAG, "sent data=%d to sabertooth driver via uart", data); +} + + + +//--------------------------- +//--------- setLeft --------- +//--------------------------- +//between 1 and 127 will control motor 1. 1 is full reverse, 64 is stop and 127 is full forward. +//Character 0 (hex 0x00) shut down both motors. +void sabertooth2x60a::setLeft(float dutyPerSigned){ + uint8_t data = 0; + if (dutyPerSigned <= -100.0) { + //full reverse for motor 1 + data = 1; + } else if (dutyPerSigned >= 100) { + //full forward + data = 127; + } else if (dutyPerSigned == 0.0) { + // Stop motor 1 + data = 64; + } else if (dutyPerSigned < 0.0) { + //scale negative values between -100 and 0 to 1-63 + data = static_cast(64 - (- dutyPerSigned / 100.0) * 63); + } else if (dutyPerSigned <= 100.0) { + //scale positive values between 0 and 100 to control motor 1 + data = static_cast(64 + (dutyPerSigned / 100.0) * 63); + } + ESP_LOGI(TAG, "set left motor to duty=%.2f, (data=%d)", dutyPerSigned, data); + sendByte(data); +} + + + +//---------------------------- +//--------- setRight --------- +//---------------------------- +//between 128 and 255 will control motor 2. 128 is full reverse, 192 is stop and 255 is full forward. +//Character 0 (hex 0x00) shut down both motors. +void sabertooth2x60a::setRight(float dutyPerSigned) { + uint8_t data = 0; + if (dutyPerSigned <= -100.0) { + // Full reverse for motor 2 + data = 128; + } else if (dutyPerSigned >= 100.0) { + // Full forward for motor 2 + data = 255; + } else if (dutyPerSigned == 0.0) { + // Stop motor 2 + data = 192; // Assuming 192 represents the stop value for motor 2 + } else if (dutyPerSigned < 0.0) { + // Scale negative values between -100 and 0 to control motor 2 + data = static_cast(192 - (-dutyPerSigned / 100.0) * 64); + } else if (dutyPerSigned <= 100.0) { + // Scale positive values between 0 and 100 to control motor 2 + data = static_cast(192 + (dutyPerSigned / 100.0) * 63); + } + + ESP_LOGI(TAG, "set right motor to duty=%.2f, (data=%d)", dutyPerSigned, data); + sendByte(data); +} + + + +//------------------------- +//--- setLeft, setRight --- +//------------------------- +//using motorCommand_t struct +void sabertooth2x60a::setLeft(motorCommand_t motorCommand_f){ + float dutyTarget = motorCommandToSignedDuty(motorCommand_f); + setLeft(dutyTarget); +} +void sabertooth2x60a::setRight(motorCommand_t motorCommand_f){ + float dutyTarget = motorCommandToSignedDuty(motorCommand_f); + setRight(dutyTarget); +} diff --git a/common/motordrivers.hpp b/common/motordrivers.hpp new file mode 100644 index 0000000..894013d --- /dev/null +++ b/common/motordrivers.hpp @@ -0,0 +1,140 @@ +#pragma once + +extern "C" +{ +#include "freertos/FreeRTOS.h" +#include "freertos/task.h" +#include "driver/gpio.h" +#include "esp_log.h" + +#include "driver/ledc.h" +#include "esp_err.h" +#include "driver/uart.h" +} + +#include + + +//==================================== +//===== single100a motor driver ====== +//==================================== + +//-------------------------------------------- +//---- struct, enum, variable declarations --- +//-------------------------------------------- +//motorstate_t, motorstateStr outsourced to common/types.hpp +#include "types.hpp" + +//struct with all config parameters for single100a motor driver +typedef struct single100a_config_t { + gpio_num_t gpio_pwm; + gpio_num_t gpio_a; + gpio_num_t gpio_b; + gpio_num_t gpio_brakeRelay; + ledc_timer_t ledc_timer; + ledc_channel_t ledc_channel; + bool aEnabledPinState; + bool bEnabledPinState; + ledc_timer_bit_t resolution; + int pwmFreq; +} single100a_config_t; + + + +//-------------------------------- +//------- single100a class ------- +//-------------------------------- +class single100a { + public: + //--- constructor --- + single100a(single100a_config_t config_f); //provide config struct (see above) + + //--- functions --- + void set(motorstate_t state, float duty_f = 0); //set mode and duty of the motor (see motorstate_t above) + void set(motorCommand_t cmd); + //TODO: add functions to get the current state and duty + + private: + //--- functions --- + void init(); //initialize pwm and gpio outputs, calculate maxDuty + + //--- variables --- + single100a_config_t config; + uint32_t dutyMax; + motorstate_t state = motorstate_t::IDLE; + bool brakeWaitingForRelay = false; + uint32_t timestamp_brakeRelayPowered; +}; + + + + + + + + + + + +//========================================== +//===== sabertooth 2x60A motor driver ====== +//========================================== + +//struct with all config parameters for sabertooth2x60a driver +typedef struct { + gpio_num_t gpio_TX; + uart_port_t uart_num; //(UART_NUM_1/2) +} sabertooth2x60_config_t; + + +//controll via simplified serial +//=> set dip switches to 'simplified serial 9600 Baud' according to manual 101011 +class sabertooth2x60a { + public: + //--- constructor --- + sabertooth2x60a(sabertooth2x60_config_t config_f); //provide config struct (see above) + //--- functions --- + //set motor speed with float value from -100 to 100 + void setLeft(float dutyPerSigned); + void setRight(float dutyPerSigned); + //set mode and duty of the motor (see motorstate_t above) + void setLeft(motorCommand_t command); + void setRight(motorCommand_t command); + //TODO: add functions to get the current state and duty + + private: + //--- functions --- + void sendByte(char data); + void init(); //initialize uart + + //--- variables --- + sabertooth2x60_config_t config; + uint32_t dutyMax; + motorstate_t state = motorstate_t::IDLE; + bool uart_isInitialized = false; +}; + + + + +// //wrap motor drivers in a common class +// //-> different drivers can be used easily without changing code in motorctl etc +// //TODO add UART as driver? +// enum driverType_t {SINGLE100A, SABERTOOTH}; +// +// template class motors_t { +// public: +// motors_t (single100a_config_t config_left, single100a_config_t config_right); +// motors_t (sabertooth2x60_config_t); +// +// setLeft(motorstate_t state); +// setRight(motorstate_t state); +// set(motorCommands_t); +// private: +// enum driverType_t driverType; +// sabertooth2x60_config_t config_saber; +// single100a_config_t config_single; +// } +// +// + diff --git a/common/speedsensor.cpp b/common/speedsensor.cpp new file mode 100644 index 0000000..22c7f2e --- /dev/null +++ b/common/speedsensor.cpp @@ -0,0 +1,171 @@ +#include "speedsensor.hpp" +#include "esp_timer.h" +#include + +//===== config ===== +#define TIMEOUT_NO_ROTATION 1000 //RPM set to 0 when no pulses within that time (ms) +static const char* TAG = "speedSensor"; + + + +uint32_t min(uint32_t a, uint32_t b){ + if (a>b) return b; + else return a; +} + + + +//========================================= +//========== ISR onEncoderChange ========== +//========================================= +//handle gpio edge event +//determines direction and rotational speed with a speedSensor object +void IRAM_ATTR onEncoderChange(void* arg) { + speedSensor* sensor = (speedSensor*)arg; + int currentState = gpio_get_level(sensor->config.gpioPin); + + //detect rising edge LOW->HIGH (reached end of gap in encoder disk) + if (currentState == 1 && sensor->prevState == 0) { + //time since last edge in us + uint32_t currentTime = esp_timer_get_time(); + uint32_t timeElapsed = currentTime - sensor->lastEdgeTime; + sensor->lastEdgeTime = currentTime; //update last edge time + + //store duration of last pulse + sensor->pulseDurations[sensor->pulseCounter] = timeElapsed; + sensor->pulseCounter++; + + //check if 3rd pulse has occoured + if (sensor->pulseCounter >= 3) { + sensor->pulseCounter = 0; //reset counter + + //simplify variable names + uint32_t pulse1 = sensor->pulseDurations[0]; + uint32_t pulse2 = sensor->pulseDurations[1]; + uint32_t pulse3 = sensor->pulseDurations[2]; + + //find shortest pulse + uint32_t shortestPulse = min(pulse1, min(pulse2, pulse3)); + + //Determine direction based on pulse order + int directionNew = 0; + if (shortestPulse == pulse1) { //short-medium-long... + directionNew = 1; //fwd + } else if (shortestPulse == pulse3) { //long-medium-short... + directionNew = -1; //rev + } else if (shortestPulse == pulse2) { + if (pulse1 < pulse3){ //medium short long-medium-short long... + directionNew = -1; //rev + } else { //long short-medium-long short-medium-long... + directionNew = 1; //fwd + } + } + + //save and invert direction if necessay + //TODO mutex? + if (sensor->config.directionInverted) sensor->direction = -directionNew; + else sensor->direction = directionNew; + + //calculate rotational speed + uint64_t pulseSum = pulse1 + pulse2 + pulse3; + sensor->currentRpm = directionNew * (sensor->config.degreePerGroup / 360.0 * 60.0 / ((double)pulseSum / 1000000.0)); + } + } + //store current pin state for next edge detection + sensor->prevState = currentState; +} + + + + +//============================ +//======= constructor ======== +//============================ +speedSensor::speedSensor(speedSensor_config_t config_f){ + //copy config + config = config_f; + //note: currently gets initialized at first method call + //this prevents crash due to too early initialization at boot + //TODO: create global objects later after boot + //init gpio and ISR + //init(); +} + + + +//========================== +//========== init ========== +//========================== + //initializes gpio pin and configures interrupt +void speedSensor::init() { + //configure pin + gpio_pad_select_gpio(config.gpioPin); + gpio_set_direction(config.gpioPin, GPIO_MODE_INPUT); + gpio_set_pull_mode(config.gpioPin, GPIO_PULLUP_ONLY); + ESP_LOGW(TAG, "%s, configured gpio-pin %d", config.logName, (int)config.gpioPin); + + //configure interrupt + gpio_set_intr_type(config.gpioPin, GPIO_INTR_ANYEDGE); + gpio_install_isr_service(0); + gpio_isr_handler_add(config.gpioPin, onEncoderChange, this); + ESP_LOGW(TAG, "%s, configured interrupt", config.logName); + + isInitialized = true; +} + + + + +//========================== +//========= getRpm ========= +//========================== +//get rotational speed in revolutions per minute +float speedSensor::getRpm(){ + //check if initialized + if (!isInitialized) init(); + uint32_t timeElapsed = esp_timer_get_time() - lastEdgeTime; + //timeout (standstill) + //TODO variable timeout considering config.degreePerGroup + if ((currentRpm != 0) && (esp_timer_get_time() - lastEdgeTime) > TIMEOUT_NO_ROTATION*1000){ + ESP_LOGW(TAG, "%s - timeout: no pulse within %dms... last pulse was %dms ago => set RPM to 0", + config.logName, TIMEOUT_NO_ROTATION, timeElapsed/1000); + currentRpm = 0; + } + //debug output (also log variables when this function is called) + ESP_LOGI(TAG, "%s - getRpm: returning stored rpm=%.3f", config.logName, currentRpm); + ESP_LOGV(TAG, "%s - rpm=%f, dir=%d, pulseCount=%d, p1=%d, p2=%d, p3=%d lastEdgetime=%d", + config.logName, + currentRpm, + direction, + pulseCounter, + (int)pulseDurations[0]/1000, + (int)pulseDurations[1]/1000, + (int)pulseDurations[2]/1000, + (int)lastEdgeTime); + + //return currently stored rpm + return currentRpm; +} + + + +//========================== +//========= getKmph ========= +//========================== +//get speed in kilometers per hour +float speedSensor::getKmph(){ + float currentSpeed = getRpm() * config.tireCircumferenceMeter * 60/1000; + ESP_LOGI(TAG, "%s - getKmph: returning speed=%.3fkm/h", config.logName, currentSpeed); + return currentSpeed; +} + + +//========================== +//========= getMps ========= +//========================== +//get speed in meters per second +float speedSensor::getMps(){ + float currentSpeed = getRpm() * config.tireCircumferenceMeter; + ESP_LOGI(TAG, "%s - getMps: returning speed=%.3fm/s", config.logName, currentSpeed); + return currentSpeed; +} diff --git a/common/speedsensor.hpp b/common/speedsensor.hpp new file mode 100644 index 0000000..c6e93bf --- /dev/null +++ b/common/speedsensor.hpp @@ -0,0 +1,54 @@ +#pragma once +extern "C" { +#include "esp_log.h" +#include "hal/gpio_types.h" +#include "driver/gpio.h" +#include "esp_timer.h" +} + +//Encoder disk requirements: +//encoder disk has to have gaps in 3 differnt intervals (short, medium, long) +//that pattern can be repeated multiple times, see config option +typedef struct { + gpio_num_t gpioPin; + float degreePerGroup; //360 / [count of short,medium,long groups on encoder disk] + float tireCircumferenceMeter; + //positive direction is pulse order "short, medium, long" + bool directionInverted; + char* logName; +} speedSensor_config_t; + + +class speedSensor { + //TODO add count of revolutions/pulses if needed? (get(), reset() etc) +public: + //constructor + speedSensor(speedSensor_config_t config); + //initializes gpio pin and configures interrupt + void init(); + + //negative values = reverse direction + //positive values = forward direction + float getKmph(); //kilometers per hour + float getMps(); //meters per second + float getRpm(); //rotations per minute + + //1=forward, -1=reverse + int direction; + + //variables for handling the encoder + speedSensor_config_t config; + int prevState = 0; + uint64_t pulseDurations[3] = {}; + uint64_t lastEdgeTime = 0; + uint8_t pulseCounter = 0; + int debugCount = 0; + double currentRpm = 0; + bool isInitialized = false; + +private: + +}; + + + diff --git a/components/ssd1306/CMakeLists.txt b/components/ssd1306/CMakeLists.txt new file mode 100644 index 0000000..ac32f0a --- /dev/null +++ b/components/ssd1306/CMakeLists.txt @@ -0,0 +1,5 @@ +set(component_srcs "ssd1306.c" "ssd1306_i2c.c" "ssd1306_spi.c") + +idf_component_register(SRCS "${component_srcs}" + PRIV_REQUIRES driver + INCLUDE_DIRS ".") diff --git a/components/ssd1306/Kconfig.projbuild b/components/ssd1306/Kconfig.projbuild new file mode 100644 index 0000000..97af991 --- /dev/null +++ b/components/ssd1306/Kconfig.projbuild @@ -0,0 +1,183 @@ +menu "SSD1306 Configuration" + + config GPIO_RANGE_MAX + int + default 33 if IDF_TARGET_ESP32 + default 46 if IDF_TARGET_ESP32S2 + default 48 if IDF_TARGET_ESP32S3 + default 18 if IDF_TARGET_ESP32C2 + default 19 if IDF_TARGET_ESP32C3 + default 30 if IDF_TARGET_ESP32C6 + + choice INTERFACE + prompt "Interface" + default I2C_INTERFACE + help + Select Interface. + config I2C_INTERFACE + bool "I2C Interface" + help + I2C Interface. + config SPI_INTERFACE + bool "SPI Interface" + help + SPI Interface. + endchoice + + choice PANEL + prompt "Panel Type" + default SSD1306_128x64 + help + Select Panel Type. + config SSD1306_128x32 + bool "128x32 Panel" + help + Panel is 128x32. + config SSD1306_128x64 + bool "128x64 Panel" + help + Panel is 128x64. + endchoice + + config OFFSETX + int "GRAM X OFFSET" + range 0 99 + default 0 + help + When your TFT have offset(X), set it. + + config FLIP + bool "Flip upside down" + default false + help + Flip upside down. + + config SCL_GPIO + depends on I2C_INTERFACE + int "SCL GPIO number" + range 0 GPIO_RANGE_MAX + default 22 if IDF_TARGET_ESP32 + default 12 if IDF_TARGET_ESP32S2 + default 12 if IDF_TARGET_ESP32S3 + default 6 # C3 and others + help + GPIO number (IOxx) to I2C SCL. + Some GPIOs are used for other purposes (flash connections, etc.) and cannot be used to I2C. + GPIOs 35-39 are input-only so cannot be used as outputs. + + config SDA_GPIO + depends on I2C_INTERFACE + int "SDA GPIO number" + range 0 GPIO_RANGE_MAX + default 21 if IDF_TARGET_ESP32 + default 11 if IDF_TARGET_ESP32S2 + default 11 if IDF_TARGET_ESP32S3 + default 5 # C3 and others + help + GPIO number (IOxx) to I2C SDA. + Some GPIOs are used for other purposes (flash connections, etc.) and cannot be used to I2C. + GPIOs 35-39 are input-only so cannot be used as outputs. + + config MOSI_GPIO + depends on SPI_INTERFACE + int "MOSI GPIO number" + range 0 GPIO_RANGE_MAX + default 23 if IDF_TARGET_ESP32 + default 35 if IDF_TARGET_ESP32S2 + default 35 if IDF_TARGET_ESP32S3 + default 1 # C3 and others + help + GPIO number (IOxx) to SPI MOSI. + Some GPIOs are used for other purposes (flash connections, etc.) and cannot be used to MOSI. + On the ESP32, GPIOs 35-39 are input-only so cannot be used as outputs. + On the ESP32-S2, GPIO 46 is input-only so cannot be used as outputs. + + config SCLK_GPIO + depends on SPI_INTERFACE + int "SCLK GPIO number" + range 0 GPIO_RANGE_MAX + default 18 if IDF_TARGET_ESP32 + default 36 if IDF_TARGET_ESP32S2 + default 36 if IDF_TARGET_ESP32S3 + default 2 # C3 and others + help + GPIO number (IOxx) to SPI SCLK. + Some GPIOs are used for other purposes (flash connections, etc.) and cannot be used to SCLK. + On the ESP32, GPIOs 35-39 are input-only so cannot be used as outputs. + On the ESP32-S2, GPIO 46 is input-only so cannot be used as outputs. + + config CS_GPIO + depends on SPI_INTERFACE + int "CS GPIO number" + range 0 GPIO_RANGE_MAX + default 5 if IDF_TARGET_ESP32 + default 34 if IDF_TARGET_ESP32S2 + default 34 if IDF_TARGET_ESP32S3 + default 10 # C3 and others + help + GPIO number (IOxx) to SPI CS. + Some GPIOs are used for other purposes (flash connections, etc.) and cannot be used to CS. + GPIOs 35-39 are input-only so cannot be used as outputs. + + config DC_GPIO + depends on SPI_INTERFACE + int "DC GPIO number" + range 0 GPIO_RANGE_MAX + default 4 if IDF_TARGET_ESP32 + default 37 if IDF_TARGET_ESP32S2 + default 37 if IDF_TARGET_ESP32S3 + default 3 # C3 and others + help + GPIO number (IOxx) to SPI DC. + Some GPIOs are used for other purposes (flash connections, etc.) and cannot be used to DC. + GPIOs 35-39 are input-only so cannot be used as outputs. + + config RESET_GPIO + int "RESET GPIO number" + range -1 GPIO_RANGE_MAX + default 15 if IDF_TARGET_ESP32 + default 38 if IDF_TARGET_ESP32S2 + default 38 if IDF_TARGET_ESP32S3 + default 4 # C3 and others + help + GPIO number (IOxx) to RESET. + When it is -1, RESET isn't performed. + Some GPIOs are used for other purposes (flash connections, etc.) and cannot be used to RESET. + GPIOs 35-39 are input-only so cannot be used as outputs. + + choice I2C_PORT + depends on I2C_INTERFACE + prompt "I2C port that controls this bus" + default I2C_PORT_0 + help + Select I2C port that controls this bus. + config I2C_PORT_0 + bool "I2C_PORT_0" + help + Use I2C_PORT_0. + config I2C_PORT_1 + depends on IDF_TARGET_ESP32 || IDF_TARGET_ESP32S2 || IDF_TARGET_ESP32S3 + bool "I2C_PORT_1" + help + Use I2C_PORT_1. + endchoice + + choice SPI_HOST + depends on SPI_INTERFACE + prompt "SPI peripheral that controls this bus" + default SPI2_HOST + help + Select SPI peripheral that controls this bus. + config SPI2_HOST + bool "SPI2_HOST" + help + Use SPI2_HOST. This is also called HSPI_HOST. + config SPI3_HOST + depends on IDF_TARGET_ESP32 || IDF_TARGET_ESP32S2 || IDF_TARGET_ESP32S3 + bool "SPI3_HOST" + help + USE SPI3_HOST. This is also called VSPI_HOST + endchoice + +endmenu + diff --git a/components/ssd1306/font8x8_basic.h b/components/ssd1306/font8x8_basic.h new file mode 100644 index 0000000..413825e --- /dev/null +++ b/components/ssd1306/font8x8_basic.h @@ -0,0 +1,174 @@ +/* + * font8x8_basic.h + * + * Created on: 2017/05/03 + * Author: yanbe + */ + +#ifndef MAIN_FONT8X8_BASIC_H_ +#define MAIN_FONT8X8_BASIC_H_ + +/* + Constant: font8x8_basic_tr + Contains an 90 digree transposed 8x8 font map for unicode points + U+0000 - U+007F (basic latin) + + To make it easy to use with SSD1306's GDDRAM mapping and API, + this constant is an 90 degree transposed. + The original version written by Marcel Sondaar is availble at: + https://github.com/dhepper/font8x8/blob/master/font8x8_basic.h + + Conversion is done via following procedure: + + for (int code = 0; code < 128; code++) { + uint8_t trans[8]; + for (int w = 0; w < 8; w++) { + trans[w] = 0x00; + for (int b = 0; b < 8; b++) { + trans[w] |= ((font8x8_basic[code][b] & (1 << w)) >> w) << b; + } + } + + for (int w = 0; w < 8; w++) { + if (w == 0) { printf(" { "); } + printf("0x%.2X", trans[w]); + if (w < 7) { printf(", "); } + if (w == 7) { printf(" }, // U+00%.2X (%c)\n", code, code); } + } + } +*/ + +static uint8_t font8x8_basic_tr[128][8] = { + { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+0000 (nul) + { 0x00, 0x04, 0x02, 0xFF, 0x02, 0x04, 0x00, 0x00 }, // U+0001 (Up Allow) + { 0x00, 0x20, 0x40, 0xFF, 0x40, 0x20, 0x00, 0x00 }, // U+0002 (Down Allow) + { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+0003 + { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+0004 + { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+0005 + { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+0006 + { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+0007 + { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+0008 + { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+0009 + { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+000A + { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+000B + { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+000C + { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+000D + { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+000E + { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+000F + { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+0010 + { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+0011 + { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+0012 + { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+0013 + { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+0014 + { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+0015 + { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+0016 + { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+0017 + { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+0018 + { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+0019 + { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+001A + { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+001B + { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+001C + { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+001D + { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+001E + { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+001F + { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+0020 (space) + { 0x00, 0x00, 0x06, 0x5F, 0x5F, 0x06, 0x00, 0x00 }, // U+0021 (!) + { 0x00, 0x03, 0x03, 0x00, 0x03, 0x03, 0x00, 0x00 }, // U+0022 (") + { 0x14, 0x7F, 0x7F, 0x14, 0x7F, 0x7F, 0x14, 0x00 }, // U+0023 (#) + { 0x24, 0x2E, 0x6B, 0x6B, 0x3A, 0x12, 0x00, 0x00 }, // U+0024 ($) + { 0x46, 0x66, 0x30, 0x18, 0x0C, 0x66, 0x62, 0x00 }, // U+0025 (%) + { 0x30, 0x7A, 0x4F, 0x5D, 0x37, 0x7A, 0x48, 0x00 }, // U+0026 (&) + { 0x04, 0x07, 0x03, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+0027 (') + { 0x00, 0x1C, 0x3E, 0x63, 0x41, 0x00, 0x00, 0x00 }, // U+0028 (() + { 0x00, 0x41, 0x63, 0x3E, 0x1C, 0x00, 0x00, 0x00 }, // U+0029 ()) + { 0x08, 0x2A, 0x3E, 0x1C, 0x1C, 0x3E, 0x2A, 0x08 }, // U+002A (*) + { 0x08, 0x08, 0x3E, 0x3E, 0x08, 0x08, 0x00, 0x00 }, // U+002B (+) + { 0x00, 0x80, 0xE0, 0x60, 0x00, 0x00, 0x00, 0x00 }, // U+002C (,) + { 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x00, 0x00 }, // U+002D (-) + { 0x00, 0x00, 0x60, 0x60, 0x00, 0x00, 0x00, 0x00 }, // U+002E (.) + { 0x60, 0x30, 0x18, 0x0C, 0x06, 0x03, 0x01, 0x00 }, // U+002F (/) + { 0x3E, 0x7F, 0x71, 0x59, 0x4D, 0x7F, 0x3E, 0x00 }, // U+0030 (0) + { 0x40, 0x42, 0x7F, 0x7F, 0x40, 0x40, 0x00, 0x00 }, // U+0031 (1) + { 0x62, 0x73, 0x59, 0x49, 0x6F, 0x66, 0x00, 0x00 }, // U+0032 (2) + { 0x22, 0x63, 0x49, 0x49, 0x7F, 0x36, 0x00, 0x00 }, // U+0033 (3) + { 0x18, 0x1C, 0x16, 0x53, 0x7F, 0x7F, 0x50, 0x00 }, // U+0034 (4) + { 0x27, 0x67, 0x45, 0x45, 0x7D, 0x39, 0x00, 0x00 }, // U+0035 (5) + { 0x3C, 0x7E, 0x4B, 0x49, 0x79, 0x30, 0x00, 0x00 }, // U+0036 (6) + { 0x03, 0x03, 0x71, 0x79, 0x0F, 0x07, 0x00, 0x00 }, // U+0037 (7) + { 0x36, 0x7F, 0x49, 0x49, 0x7F, 0x36, 0x00, 0x00 }, // U+0038 (8) + { 0x06, 0x4F, 0x49, 0x69, 0x3F, 0x1E, 0x00, 0x00 }, // U+0039 (9) + { 0x00, 0x00, 0x66, 0x66, 0x00, 0x00, 0x00, 0x00 }, // U+003A (:) + { 0x00, 0x80, 0xE6, 0x66, 0x00, 0x00, 0x00, 0x00 }, // U+003B (;) + { 0x08, 0x1C, 0x36, 0x63, 0x41, 0x00, 0x00, 0x00 }, // U+003C (<) + { 0x24, 0x24, 0x24, 0x24, 0x24, 0x24, 0x00, 0x00 }, // U+003D (=) + { 0x00, 0x41, 0x63, 0x36, 0x1C, 0x08, 0x00, 0x00 }, // U+003E (>) + { 0x02, 0x03, 0x51, 0x59, 0x0F, 0x06, 0x00, 0x00 }, // U+003F (?) + { 0x3E, 0x7F, 0x41, 0x5D, 0x5D, 0x1F, 0x1E, 0x00 }, // U+0040 (@) + { 0x7C, 0x7E, 0x13, 0x13, 0x7E, 0x7C, 0x00, 0x00 }, // U+0041 (A) + { 0x41, 0x7F, 0x7F, 0x49, 0x49, 0x7F, 0x36, 0x00 }, // U+0042 (B) + { 0x1C, 0x3E, 0x63, 0x41, 0x41, 0x63, 0x22, 0x00 }, // U+0043 (C) + { 0x41, 0x7F, 0x7F, 0x41, 0x63, 0x3E, 0x1C, 0x00 }, // U+0044 (D) + { 0x41, 0x7F, 0x7F, 0x49, 0x5D, 0x41, 0x63, 0x00 }, // U+0045 (E) + { 0x41, 0x7F, 0x7F, 0x49, 0x1D, 0x01, 0x03, 0x00 }, // U+0046 (F) + { 0x1C, 0x3E, 0x63, 0x41, 0x51, 0x73, 0x72, 0x00 }, // U+0047 (G) + { 0x7F, 0x7F, 0x08, 0x08, 0x7F, 0x7F, 0x00, 0x00 }, // U+0048 (H) + { 0x00, 0x41, 0x7F, 0x7F, 0x41, 0x00, 0x00, 0x00 }, // U+0049 (I) + { 0x30, 0x70, 0x40, 0x41, 0x7F, 0x3F, 0x01, 0x00 }, // U+004A (J) + { 0x41, 0x7F, 0x7F, 0x08, 0x1C, 0x77, 0x63, 0x00 }, // U+004B (K) + { 0x41, 0x7F, 0x7F, 0x41, 0x40, 0x60, 0x70, 0x00 }, // U+004C (L) + { 0x7F, 0x7F, 0x0E, 0x1C, 0x0E, 0x7F, 0x7F, 0x00 }, // U+004D (M) + { 0x7F, 0x7F, 0x06, 0x0C, 0x18, 0x7F, 0x7F, 0x00 }, // U+004E (N) + { 0x1C, 0x3E, 0x63, 0x41, 0x63, 0x3E, 0x1C, 0x00 }, // U+004F (O) + { 0x41, 0x7F, 0x7F, 0x49, 0x09, 0x0F, 0x06, 0x00 }, // U+0050 (P) + { 0x1E, 0x3F, 0x21, 0x71, 0x7F, 0x5E, 0x00, 0x00 }, // U+0051 (Q) + { 0x41, 0x7F, 0x7F, 0x09, 0x19, 0x7F, 0x66, 0x00 }, // U+0052 (R) + { 0x26, 0x6F, 0x4D, 0x59, 0x73, 0x32, 0x00, 0x00 }, // U+0053 (S) + { 0x03, 0x41, 0x7F, 0x7F, 0x41, 0x03, 0x00, 0x00 }, // U+0054 (T) + { 0x7F, 0x7F, 0x40, 0x40, 0x7F, 0x7F, 0x00, 0x00 }, // U+0055 (U) + { 0x1F, 0x3F, 0x60, 0x60, 0x3F, 0x1F, 0x00, 0x00 }, // U+0056 (V) + { 0x7F, 0x7F, 0x30, 0x18, 0x30, 0x7F, 0x7F, 0x00 }, // U+0057 (W) + { 0x43, 0x67, 0x3C, 0x18, 0x3C, 0x67, 0x43, 0x00 }, // U+0058 (X) + { 0x07, 0x4F, 0x78, 0x78, 0x4F, 0x07, 0x00, 0x00 }, // U+0059 (Y) + { 0x47, 0x63, 0x71, 0x59, 0x4D, 0x67, 0x73, 0x00 }, // U+005A (Z) + { 0x00, 0x7F, 0x7F, 0x41, 0x41, 0x00, 0x00, 0x00 }, // U+005B ([) + { 0x01, 0x03, 0x06, 0x0C, 0x18, 0x30, 0x60, 0x00 }, // U+005C (\) + { 0x00, 0x41, 0x41, 0x7F, 0x7F, 0x00, 0x00, 0x00 }, // U+005D (]) + { 0x08, 0x0C, 0x06, 0x03, 0x06, 0x0C, 0x08, 0x00 }, // U+005E (^) + { 0x80, 0x80, 0x80, 0x80, 0x80, 0x80, 0x80, 0x80 }, // U+005F (_) + { 0x00, 0x00, 0x03, 0x07, 0x04, 0x00, 0x00, 0x00 }, // U+0060 (`) + { 0x20, 0x74, 0x54, 0x54, 0x3C, 0x78, 0x40, 0x00 }, // U+0061 (a) + { 0x41, 0x7F, 0x3F, 0x48, 0x48, 0x78, 0x30, 0x00 }, // U+0062 (b) + { 0x38, 0x7C, 0x44, 0x44, 0x6C, 0x28, 0x00, 0x00 }, // U+0063 (c) + { 0x30, 0x78, 0x48, 0x49, 0x3F, 0x7F, 0x40, 0x00 }, // U+0064 (d) + { 0x38, 0x7C, 0x54, 0x54, 0x5C, 0x18, 0x00, 0x00 }, // U+0065 (e) + { 0x48, 0x7E, 0x7F, 0x49, 0x03, 0x02, 0x00, 0x00 }, // U+0066 (f) + { 0x98, 0xBC, 0xA4, 0xA4, 0xF8, 0x7C, 0x04, 0x00 }, // U+0067 (g) + { 0x41, 0x7F, 0x7F, 0x08, 0x04, 0x7C, 0x78, 0x00 }, // U+0068 (h) + { 0x00, 0x44, 0x7D, 0x7D, 0x40, 0x00, 0x00, 0x00 }, // U+0069 (i) + { 0x60, 0xE0, 0x80, 0x80, 0xFD, 0x7D, 0x00, 0x00 }, // U+006A (j) + { 0x41, 0x7F, 0x7F, 0x10, 0x38, 0x6C, 0x44, 0x00 }, // U+006B (k) + { 0x00, 0x41, 0x7F, 0x7F, 0x40, 0x00, 0x00, 0x00 }, // U+006C (l) + { 0x7C, 0x7C, 0x18, 0x38, 0x1C, 0x7C, 0x78, 0x00 }, // U+006D (m) + { 0x7C, 0x7C, 0x04, 0x04, 0x7C, 0x78, 0x00, 0x00 }, // U+006E (n) + { 0x38, 0x7C, 0x44, 0x44, 0x7C, 0x38, 0x00, 0x00 }, // U+006F (o) + { 0x84, 0xFC, 0xF8, 0xA4, 0x24, 0x3C, 0x18, 0x00 }, // U+0070 (p) + { 0x18, 0x3C, 0x24, 0xA4, 0xF8, 0xFC, 0x84, 0x00 }, // U+0071 (q) + { 0x44, 0x7C, 0x78, 0x4C, 0x04, 0x1C, 0x18, 0x00 }, // U+0072 (r) + { 0x48, 0x5C, 0x54, 0x54, 0x74, 0x24, 0x00, 0x00 }, // U+0073 (s) + { 0x00, 0x04, 0x3E, 0x7F, 0x44, 0x24, 0x00, 0x00 }, // U+0074 (t) + { 0x3C, 0x7C, 0x40, 0x40, 0x3C, 0x7C, 0x40, 0x00 }, // U+0075 (u) + { 0x1C, 0x3C, 0x60, 0x60, 0x3C, 0x1C, 0x00, 0x00 }, // U+0076 (v) + { 0x3C, 0x7C, 0x70, 0x38, 0x70, 0x7C, 0x3C, 0x00 }, // U+0077 (w) + { 0x44, 0x6C, 0x38, 0x10, 0x38, 0x6C, 0x44, 0x00 }, // U+0078 (x) + { 0x9C, 0xBC, 0xA0, 0xA0, 0xFC, 0x7C, 0x00, 0x00 }, // U+0079 (y) + { 0x4C, 0x64, 0x74, 0x5C, 0x4C, 0x64, 0x00, 0x00 }, // U+007A (z) + { 0x08, 0x08, 0x3E, 0x77, 0x41, 0x41, 0x00, 0x00 }, // U+007B ({) + { 0x00, 0x00, 0x00, 0x77, 0x77, 0x00, 0x00, 0x00 }, // U+007C (|) + { 0x41, 0x41, 0x77, 0x3E, 0x08, 0x08, 0x00, 0x00 }, // U+007D (}) + { 0x02, 0x03, 0x01, 0x03, 0x02, 0x03, 0x01, 0x00 }, // U+007E (~) + { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 } // U+007F +}; + +#endif /* MAIN_FONT8X8_BASIC_H_ */ + + diff --git a/components/ssd1306/ssd1306.c b/components/ssd1306/ssd1306.c new file mode 100644 index 0000000..f5d97f3 --- /dev/null +++ b/components/ssd1306/ssd1306.c @@ -0,0 +1,619 @@ +#include + +#include "freertos/FreeRTOS.h" +#include "freertos/task.h" + +#include "esp_log.h" + +#include "ssd1306.h" +#include "font8x8_basic.h" + +#define TAG "SSD1306" + +#define PACK8 __attribute__((aligned( __alignof__( uint8_t ) ), packed )) + +typedef union out_column_t { + uint32_t u32; + uint8_t u8[4]; +} PACK8 out_column_t; + +void ssd1306_init(SSD1306_t * dev, int width, int height) +{ + if (dev->_address == SPIAddress) { + spi_init(dev, width, height); + } else { + i2c_init(dev, width, height); + } + // Initialize internal buffer + for (int i=0;i_pages;i++) { + memset(dev->_page[i]._segs, 0, 128); + } +} + +int ssd1306_get_width(SSD1306_t * dev) +{ + return dev->_width; +} + +int ssd1306_get_height(SSD1306_t * dev) +{ + return dev->_height; +} + +int ssd1306_get_pages(SSD1306_t * dev) +{ + return dev->_pages; +} + +void ssd1306_show_buffer(SSD1306_t * dev) +{ + if (dev->_address == SPIAddress) { + for (int page=0; page_pages;page++) { + spi_display_image(dev, page, 0, dev->_page[page]._segs, dev->_width); + } + } else { + for (int page=0; page_pages;page++) { + i2c_display_image(dev, page, 0, dev->_page[page]._segs, dev->_width); + } + } +} + +void ssd1306_set_buffer(SSD1306_t * dev, uint8_t * buffer) +{ + int index = 0; + for (int page=0; page_pages;page++) { + memcpy(&dev->_page[page]._segs, &buffer[index], 128); + index = index + 128; + } +} + +void ssd1306_get_buffer(SSD1306_t * dev, uint8_t * buffer) +{ + int index = 0; + for (int page=0; page_pages;page++) { + memcpy(&buffer[index], &dev->_page[page]._segs, 128); + index = index + 128; + } +} + +void ssd1306_display_image(SSD1306_t * dev, int page, int seg, uint8_t * images, int width) +{ + if (dev->_address == SPIAddress) { + spi_display_image(dev, page, seg, images, width); + } else { + i2c_display_image(dev, page, seg, images, width); + } + // Set to internal buffer + memcpy(&dev->_page[page]._segs[seg], images, width); +} + +void ssd1306_display_text(SSD1306_t * dev, int page, char * text, int text_len, bool invert) +{ + if (page >= dev->_pages) return; + int _text_len = text_len; + if (_text_len > 16) _text_len = 16; + + uint8_t seg = 0; + uint8_t image[8]; + for (uint8_t i = 0; i < _text_len; i++) { + memcpy(image, font8x8_basic_tr[(uint8_t)text[i]], 8); + if (invert) ssd1306_invert(image, 8); + if (dev->_flip) ssd1306_flip(image, 8); + ssd1306_display_image(dev, page, seg, image, 8); +#if 0 + if (dev->_address == SPIAddress) { + spi_display_image(dev, page, seg, image, 8); + } else { + i2c_display_image(dev, page, seg, image, 8); + } +#endif + seg = seg + 8; + } +} + +// by Coert Vonk +void +ssd1306_display_text_x3(SSD1306_t * dev, int page, char * text, int text_len, bool invert) +{ + if (page >= dev->_pages) return; + int _text_len = text_len; + if (_text_len > 5) _text_len = 5; + + uint8_t seg = 0; + + for (uint8_t nn = 0; nn < _text_len; nn++) { + + uint8_t const * const in_columns = font8x8_basic_tr[(uint8_t)text[nn]]; + + // make the character 3x as high + out_column_t out_columns[8]; + memset(out_columns, 0, sizeof(out_columns)); + + for (uint8_t xx = 0; xx < 8; xx++) { // for each column (x-direction) + + uint32_t in_bitmask = 0b1; + uint32_t out_bitmask = 0b111; + + for (uint8_t yy = 0; yy < 8; yy++) { // for pixel (y-direction) + if (in_columns[xx] & in_bitmask) { + out_columns[xx].u32 |= out_bitmask; + } + in_bitmask <<= 1; + out_bitmask <<= 3; + } + } + + // render character in 8 column high pieces, making them 3x as wide + for (uint8_t yy = 0; yy < 3; yy++) { // for each group of 8 pixels high (y-direction) + + uint8_t image[24]; + for (uint8_t xx = 0; xx < 8; xx++) { // for each column (x-direction) + image[xx*3+0] = + image[xx*3+1] = + image[xx*3+2] = out_columns[xx].u8[yy]; + } + if (invert) ssd1306_invert(image, 24); + if (dev->_flip) ssd1306_flip(image, 24); + if (dev->_address == SPIAddress) { + spi_display_image(dev, page+yy, seg, image, 24); + } else { + i2c_display_image(dev, page+yy, seg, image, 24); + } + memcpy(&dev->_page[page+yy]._segs[seg], image, 24); + } + seg = seg + 24; + } +} + +void ssd1306_clear_screen(SSD1306_t * dev, bool invert) +{ + char space[16]; + memset(space, 0x00, sizeof(space)); + for (int page = 0; page < dev->_pages; page++) { + ssd1306_display_text(dev, page, space, sizeof(space), invert); + } +} + +void ssd1306_clear_line(SSD1306_t * dev, int page, bool invert) +{ + char space[16]; + memset(space, 0x00, sizeof(space)); + ssd1306_display_text(dev, page, space, sizeof(space), invert); +} + +void ssd1306_contrast(SSD1306_t * dev, int contrast) +{ + if (dev->_address == SPIAddress) { + spi_contrast(dev, contrast); + } else { + i2c_contrast(dev, contrast); + } +} + +void ssd1306_software_scroll(SSD1306_t * dev, int start, int end) +{ + ESP_LOGD(TAG, "software_scroll start=%d end=%d _pages=%d", start, end, dev->_pages); + if (start < 0 || end < 0) { + dev->_scEnable = false; + } else if (start >= dev->_pages || end >= dev->_pages) { + dev->_scEnable = false; + } else { + dev->_scEnable = true; + dev->_scStart = start; + dev->_scEnd = end; + dev->_scDirection = 1; + if (start > end ) dev->_scDirection = -1; + } +} + + +void ssd1306_scroll_text(SSD1306_t * dev, char * text, int text_len, bool invert) +{ + ESP_LOGD(TAG, "dev->_scEnable=%d", dev->_scEnable); + if (dev->_scEnable == false) return; + + void (*func)(SSD1306_t * dev, int page, int seg, uint8_t * images, int width); + if (dev->_address == SPIAddress) { + func = spi_display_image; + } else { + func = i2c_display_image; + } + + int srcIndex = dev->_scEnd - dev->_scDirection; + while(1) { + int dstIndex = srcIndex + dev->_scDirection; + ESP_LOGD(TAG, "srcIndex=%d dstIndex=%d", srcIndex,dstIndex); + for(int seg = 0; seg < dev->_width; seg++) { + dev->_page[dstIndex]._segs[seg] = dev->_page[srcIndex]._segs[seg]; + } + (*func)(dev, dstIndex, 0, dev->_page[dstIndex]._segs, sizeof(dev->_page[dstIndex]._segs)); + if (srcIndex == dev->_scStart) break; + srcIndex = srcIndex - dev->_scDirection; + } + + int _text_len = text_len; + if (_text_len > 16) _text_len = 16; + + ssd1306_display_text(dev, srcIndex, text, text_len, invert); +} + +void ssd1306_scroll_clear(SSD1306_t * dev) +{ + ESP_LOGD(TAG, "dev->_scEnable=%d", dev->_scEnable); + if (dev->_scEnable == false) return; + + int srcIndex = dev->_scEnd - dev->_scDirection; + while(1) { + int dstIndex = srcIndex + dev->_scDirection; + ESP_LOGD(TAG, "srcIndex=%d dstIndex=%d", srcIndex,dstIndex); + ssd1306_clear_line(dev, dstIndex, false); + if (dstIndex == dev->_scStart) break; + srcIndex = srcIndex - dev->_scDirection; + } +} + + +void ssd1306_hardware_scroll(SSD1306_t * dev, ssd1306_scroll_type_t scroll) +{ + if (dev->_address == SPIAddress) { + spi_hardware_scroll(dev, scroll); + } else { + i2c_hardware_scroll(dev, scroll); + } +} + +// delay = 0 : display with no wait +// delay > 0 : display with wait +// delay < 0 : no display +void ssd1306_wrap_arround(SSD1306_t * dev, ssd1306_scroll_type_t scroll, int start, int end, int8_t delay) +{ + if (scroll == SCROLL_RIGHT) { + int _start = start; // 0 to 7 + int _end = end; // 0 to 7 + if (_end >= dev->_pages) _end = dev->_pages - 1; + uint8_t wk; + //for (int page=0;page_pages;page++) { + for (int page=_start;page<=_end;page++) { + wk = dev->_page[page]._segs[127]; + for (int seg=127;seg>0;seg--) { + dev->_page[page]._segs[seg] = dev->_page[page]._segs[seg-1]; + } + dev->_page[page]._segs[0] = wk; + } + + } else if (scroll == SCROLL_LEFT) { + int _start = start; // 0 to 7 + int _end = end; // 0 to 7 + if (_end >= dev->_pages) _end = dev->_pages - 1; + uint8_t wk; + //for (int page=0;page_pages;page++) { + for (int page=_start;page<=_end;page++) { + wk = dev->_page[page]._segs[0]; + for (int seg=0;seg<127;seg++) { + dev->_page[page]._segs[seg] = dev->_page[page]._segs[seg+1]; + } + dev->_page[page]._segs[127] = wk; + } + + } else if (scroll == SCROLL_UP) { + int _start = start; // 0 to {width-1} + int _end = end; // 0 to {width-1} + if (_end >= dev->_width) _end = dev->_width - 1; + uint8_t wk0; + uint8_t wk1; + uint8_t wk2; + uint8_t save[128]; + // Save pages 0 + for (int seg=0;seg<128;seg++) { + save[seg] = dev->_page[0]._segs[seg]; + } + // Page0 to Page6 + for (int page=0;page_pages-1;page++) { + //for (int seg=0;seg<128;seg++) { + for (int seg=_start;seg<=_end;seg++) { + wk0 = dev->_page[page]._segs[seg]; + wk1 = dev->_page[page+1]._segs[seg]; + if (dev->_flip) wk0 = ssd1306_rotate_byte(wk0); + if (dev->_flip) wk1 = ssd1306_rotate_byte(wk1); + if (seg == 0) { + ESP_LOGD(TAG, "b page=%d wk0=%02x wk1=%02x", page, wk0, wk1); + } + wk0 = wk0 >> 1; + wk1 = wk1 & 0x01; + wk1 = wk1 << 7; + wk2 = wk0 | wk1; + if (seg == 0) { + ESP_LOGD(TAG, "a page=%d wk0=%02x wk1=%02x wk2=%02x", page, wk0, wk1, wk2); + } + if (dev->_flip) wk2 = ssd1306_rotate_byte(wk2); + dev->_page[page]._segs[seg] = wk2; + } + } + // Page7 + int pages = dev->_pages-1; + //for (int seg=0;seg<128;seg++) { + for (int seg=_start;seg<=_end;seg++) { + wk0 = dev->_page[pages]._segs[seg]; + wk1 = save[seg]; + if (dev->_flip) wk0 = ssd1306_rotate_byte(wk0); + if (dev->_flip) wk1 = ssd1306_rotate_byte(wk1); + wk0 = wk0 >> 1; + wk1 = wk1 & 0x01; + wk1 = wk1 << 7; + wk2 = wk0 | wk1; + if (dev->_flip) wk2 = ssd1306_rotate_byte(wk2); + dev->_page[pages]._segs[seg] = wk2; + } + + } else if (scroll == SCROLL_DOWN) { + int _start = start; // 0 to {width-1} + int _end = end; // 0 to {width-1} + if (_end >= dev->_width) _end = dev->_width - 1; + uint8_t wk0; + uint8_t wk1; + uint8_t wk2; + uint8_t save[128]; + // Save pages 7 + int pages = dev->_pages-1; + for (int seg=0;seg<128;seg++) { + save[seg] = dev->_page[pages]._segs[seg]; + } + // Page7 to Page1 + for (int page=pages;page>0;page--) { + //for (int seg=0;seg<128;seg++) { + for (int seg=_start;seg<=_end;seg++) { + wk0 = dev->_page[page]._segs[seg]; + wk1 = dev->_page[page-1]._segs[seg]; + if (dev->_flip) wk0 = ssd1306_rotate_byte(wk0); + if (dev->_flip) wk1 = ssd1306_rotate_byte(wk1); + if (seg == 0) { + ESP_LOGD(TAG, "b page=%d wk0=%02x wk1=%02x", page, wk0, wk1); + } + wk0 = wk0 << 1; + wk1 = wk1 & 0x80; + wk1 = wk1 >> 7; + wk2 = wk0 | wk1; + if (seg == 0) { + ESP_LOGD(TAG, "a page=%d wk0=%02x wk1=%02x wk2=%02x", page, wk0, wk1, wk2); + } + if (dev->_flip) wk2 = ssd1306_rotate_byte(wk2); + dev->_page[page]._segs[seg] = wk2; + } + } + // Page0 + //for (int seg=0;seg<128;seg++) { + for (int seg=_start;seg<=_end;seg++) { + wk0 = dev->_page[0]._segs[seg]; + wk1 = save[seg]; + if (dev->_flip) wk0 = ssd1306_rotate_byte(wk0); + if (dev->_flip) wk1 = ssd1306_rotate_byte(wk1); + wk0 = wk0 << 1; + wk1 = wk1 & 0x80; + wk1 = wk1 >> 7; + wk2 = wk0 | wk1; + if (dev->_flip) wk2 = ssd1306_rotate_byte(wk2); + dev->_page[0]._segs[seg] = wk2; + } + + } + + if (delay >= 0) { + for (int page=0;page_pages;page++) { + if (dev->_address == SPIAddress) { + spi_display_image(dev, page, 0, dev->_page[page]._segs, 128); + } else { + i2c_display_image(dev, page, 0, dev->_page[page]._segs, 128); + } + if (delay) vTaskDelay(delay); + } + } + +} + +void ssd1306_bitmaps(SSD1306_t * dev, int xpos, int ypos, uint8_t * bitmap, int width, int height, bool invert) +{ + if ( (width % 8) != 0) { + ESP_LOGE(TAG, "width must be a multiple of 8"); + return; + } + int _width = width / 8; + uint8_t wk0; + uint8_t wk1; + uint8_t wk2; + uint8_t page = (ypos / 8); + uint8_t _seg = xpos; + uint8_t dstBits = (ypos % 8); + ESP_LOGD(TAG, "ypos=%d page=%d dstBits=%d", ypos, page, dstBits); + int offset = 0; + for(int _height=0;_height=0; srcBits--) { + wk0 = dev->_page[page]._segs[_seg]; + if (dev->_flip) wk0 = ssd1306_rotate_byte(wk0); + + wk1 = bitmap[index+offset]; + if (invert) wk1 = ~wk1; + + //wk2 = ssd1306_copy_bit(bitmap[index+offset], srcBits, wk0, dstBits); + wk2 = ssd1306_copy_bit(wk1, srcBits, wk0, dstBits); + if (dev->_flip) wk2 = ssd1306_rotate_byte(wk2); + + ESP_LOGD(TAG, "index=%d offset=%d page=%d _seg=%d, wk2=%02x", index, offset, page, _seg, wk2); + dev->_page[page]._segs[_seg] = wk2; + _seg++; + } + } + vTaskDelay(1); + offset = offset + _width; + dstBits++; + _seg = xpos; + if (dstBits == 8) { + page++; + dstBits=0; + } + } + +#if 0 + for (int _seg=ypos;_seg_page[_page]._segs[_seg]; + uint8_t wk1 = 1 << _bits; + ESP_LOGD(TAG, "ypos=%d _page=%d _bits=%d wk0=0x%02x wk1=0x%02x", ypos, _page, _bits, wk0, wk1); + if (invert) { + wk0 = wk0 & ~wk1; + } else { + wk0 = wk0 | wk1; + } + if (dev->_flip) wk0 = ssd1306_rotate_byte(wk0); + ESP_LOGD(TAG, "wk0=0x%02x wk1=0x%02x", wk0, wk1); + dev->_page[_page]._segs[_seg] = wk0; +} + +// Set line to internal buffer. Not show it. +void _ssd1306_line(SSD1306_t * dev, int x1, int y1, int x2, int y2, bool invert) +{ + int i; + int dx,dy; + int sx,sy; + int E; + + /* distance between two points */ + dx = ( x2 > x1 ) ? x2 - x1 : x1 - x2; + dy = ( y2 > y1 ) ? y2 - y1 : y1 - y2; + + /* direction of two point */ + sx = ( x2 > x1 ) ? 1 : -1; + sy = ( y2 > y1 ) ? 1 : -1; + + /* inclination < 1 */ + if ( dx > dy ) { + E = -dx; + for ( i = 0 ; i <= dx ; i++ ) { + _ssd1306_pixel(dev, x1, y1, invert); + x1 += sx; + E += 2 * dy; + if ( E >= 0 ) { + y1 += sy; + E -= 2 * dx; + } + } + + /* inclination >= 1 */ + } else { + E = -dy; + for ( i = 0 ; i <= dy ; i++ ) { + _ssd1306_pixel(dev, x1, y1, invert); + y1 += sy; + E += 2 * dx; + if ( E >= 0 ) { + x1 += sx; + E -= 2 * dy; + } + } + } +} + +void ssd1306_invert(uint8_t *buf, size_t blen) +{ + uint8_t wk; + for(int i=0; i0x48 +uint8_t ssd1306_rotate_byte(uint8_t ch1) { + uint8_t ch2 = 0; + for (int j=0;j<8;j++) { + ch2 = (ch2 << 1) + (ch1 & 0x01); + ch1 = ch1 >> 1; + } + return ch2; +} + + +void ssd1306_fadeout(SSD1306_t * dev) +{ + void (*func)(SSD1306_t * dev, int page, int seg, uint8_t * images, int width); + if (dev->_address == SPIAddress) { + func = spi_display_image; + } else { + func = i2c_display_image; + } + + uint8_t image[1]; + for(int page=0; page_pages; page++) { + image[0] = 0xFF; + for(int line=0; line<8; line++) { + if (dev->_flip) { + image[0] = image[0] >> 1; + } else { + image[0] = image[0] << 1; + } + for(int seg=0; seg<128; seg++) { + (*func)(dev, page, seg, image, 1); + dev->_page[page]._segs[seg] = image[0]; + } + } + } +} + +void ssd1306_dump(SSD1306_t dev) +{ + printf("_address=%x\n",dev._address); + printf("_width=%x\n",dev._width); + printf("_height=%x\n",dev._height); + printf("_pages=%x\n",dev._pages); +} + +void ssd1306_dump_page(SSD1306_t * dev, int page, int seg) +{ + ESP_LOGI(TAG, "dev->_page[%d]._segs[%d]=%02x", page, seg, dev->_page[page]._segs[seg]); +} + diff --git a/components/ssd1306/ssd1306.h b/components/ssd1306/ssd1306.h new file mode 100644 index 0000000..120315d --- /dev/null +++ b/components/ssd1306/ssd1306.h @@ -0,0 +1,157 @@ +#ifndef MAIN_SSD1306_H_ +#define MAIN_SSD1306_H_ + +#include "driver/spi_master.h" + +// Following definitions are bollowed from +// http://robotcantalk.blogspot.com/2015/03/interfacing-arduino-with-ssd1306-driven.html + +/* Control byte for i2c +Co : bit 8 : Continuation Bit + * 1 = no-continuation (only one byte to follow) + * 0 = the controller should expect a stream of bytes. +D/C# : bit 7 : Data/Command Select bit + * 1 = the next byte or byte stream will be Data. + * 0 = a Command byte or byte stream will be coming up next. + Bits 6-0 will be all zeros. +Usage: +0x80 : Single Command byte +0x00 : Command Stream +0xC0 : Single Data byte +0x40 : Data Stream +*/ +#define OLED_CONTROL_BYTE_CMD_SINGLE 0x80 +#define OLED_CONTROL_BYTE_CMD_STREAM 0x00 +#define OLED_CONTROL_BYTE_DATA_SINGLE 0xC0 +#define OLED_CONTROL_BYTE_DATA_STREAM 0x40 + +// Fundamental commands (pg.28) +#define OLED_CMD_SET_CONTRAST 0x81 // follow with 0x7F +#define OLED_CMD_DISPLAY_RAM 0xA4 +#define OLED_CMD_DISPLAY_ALLON 0xA5 +#define OLED_CMD_DISPLAY_NORMAL 0xA6 +#define OLED_CMD_DISPLAY_INVERTED 0xA7 +#define OLED_CMD_DISPLAY_OFF 0xAE +#define OLED_CMD_DISPLAY_ON 0xAF + +// Addressing Command Table (pg.30) +#define OLED_CMD_SET_MEMORY_ADDR_MODE 0x20 +#define OLED_CMD_SET_HORI_ADDR_MODE 0x00 // Horizontal Addressing Mode +#define OLED_CMD_SET_VERT_ADDR_MODE 0x01 // Vertical Addressing Mode +#define OLED_CMD_SET_PAGE_ADDR_MODE 0x02 // Page Addressing Mode +#define OLED_CMD_SET_COLUMN_RANGE 0x21 // can be used only in HORZ/VERT mode - follow with 0x00 and 0x7F = COL127 +#define OLED_CMD_SET_PAGE_RANGE 0x22 // can be used only in HORZ/VERT mode - follow with 0x00 and 0x07 = PAGE7 + +// Hardware Config (pg.31) +#define OLED_CMD_SET_DISPLAY_START_LINE 0x40 +#define OLED_CMD_SET_SEGMENT_REMAP_0 0xA0 +#define OLED_CMD_SET_SEGMENT_REMAP_1 0xA1 +#define OLED_CMD_SET_MUX_RATIO 0xA8 // follow with 0x3F = 64 MUX +#define OLED_CMD_SET_COM_SCAN_MODE 0xC8 +#define OLED_CMD_SET_DISPLAY_OFFSET 0xD3 // follow with 0x00 +#define OLED_CMD_SET_COM_PIN_MAP 0xDA // follow with 0x12 +#define OLED_CMD_NOP 0xE3 // NOP + +// Timing and Driving Scheme (pg.32) +#define OLED_CMD_SET_DISPLAY_CLK_DIV 0xD5 // follow with 0x80 +#define OLED_CMD_SET_PRECHARGE 0xD9 // follow with 0xF1 +#define OLED_CMD_SET_VCOMH_DESELCT 0xDB // follow with 0x30 + +// Charge Pump (pg.62) +#define OLED_CMD_SET_CHARGE_PUMP 0x8D // follow with 0x14 + +// Scrolling Command +#define OLED_CMD_HORIZONTAL_RIGHT 0x26 +#define OLED_CMD_HORIZONTAL_LEFT 0x27 +#define OLED_CMD_CONTINUOUS_SCROLL 0x29 +#define OLED_CMD_DEACTIVE_SCROLL 0x2E +#define OLED_CMD_ACTIVE_SCROLL 0x2F +#define OLED_CMD_VERTICAL 0xA3 + +#define I2CAddress 0x3C +#define SPIAddress 0xFF + +typedef enum { + SCROLL_RIGHT = 1, + SCROLL_LEFT = 2, + SCROLL_DOWN = 3, + SCROLL_UP = 4, + SCROLL_STOP = 5 +} ssd1306_scroll_type_t; + +typedef struct { + bool _valid; // Not using it anymore + int _segLen; // Not using it anymore + uint8_t _segs[128]; +} PAGE_t; + +typedef struct { + int _address; + int _width; + int _height; + int _pages; + int _dc; + spi_device_handle_t _SPIHandle; + bool _scEnable; + int _scStart; + int _scEnd; + int _scDirection; + PAGE_t _page[8]; + bool _flip; +} SSD1306_t; + +#ifdef __cplusplus +extern "C" +{ +#endif + +void ssd1306_init(SSD1306_t * dev, int width, int height); +int ssd1306_get_width(SSD1306_t * dev); +int ssd1306_get_height(SSD1306_t * dev); +int ssd1306_get_pages(SSD1306_t * dev); +void ssd1306_show_buffer(SSD1306_t * dev); +void ssd1306_set_buffer(SSD1306_t * dev, uint8_t * buffer); +void ssd1306_get_buffer(SSD1306_t * dev, uint8_t * buffer); +void ssd1306_display_image(SSD1306_t * dev, int page, int seg, uint8_t * images, int width); +void ssd1306_display_text(SSD1306_t * dev, int page, char * text, int text_len, bool invert); +void ssd1306_display_text_x3(SSD1306_t * dev, int page, char * text, int text_len, bool invert); +void ssd1306_clear_screen(SSD1306_t * dev, bool invert); +void ssd1306_clear_line(SSD1306_t * dev, int page, bool invert); +void ssd1306_contrast(SSD1306_t * dev, int contrast); +void ssd1306_software_scroll(SSD1306_t * dev, int start, int end); +void ssd1306_scroll_text(SSD1306_t * dev, char * text, int text_len, bool invert); +void ssd1306_scroll_clear(SSD1306_t * dev); +void ssd1306_hardware_scroll(SSD1306_t * dev, ssd1306_scroll_type_t scroll); +void ssd1306_wrap_arround(SSD1306_t * dev, ssd1306_scroll_type_t scroll, int start, int end, int8_t delay); +void ssd1306_bitmaps(SSD1306_t * dev, int xpos, int ypos, uint8_t * bitmap, int width, int height, bool invert); +void _ssd1306_pixel(SSD1306_t * dev, int xpos, int ypos, bool invert); +void _ssd1306_line(SSD1306_t * dev, int x1, int y1, int x2, int y2, bool invert); +void ssd1306_invert(uint8_t *buf, size_t blen); +void ssd1306_flip(uint8_t *buf, size_t blen); +uint8_t ssd1306_copy_bit(uint8_t src, int srcBits, uint8_t dst, int dstBits); +uint8_t ssd1306_rotate_byte(uint8_t ch1); +void ssd1306_fadeout(SSD1306_t * dev); +void ssd1306_dump(SSD1306_t dev); +void ssd1306_dump_page(SSD1306_t * dev, int page, int seg); + +void i2c_master_init(SSD1306_t * dev, int16_t sda, int16_t scl, int16_t reset); +void i2c_init(SSD1306_t * dev, int width, int height); +void i2c_display_image(SSD1306_t * dev, int page, int seg, uint8_t * images, int width); +void i2c_contrast(SSD1306_t * dev, int contrast); +void i2c_hardware_scroll(SSD1306_t * dev, ssd1306_scroll_type_t scroll); + +void spi_master_init(SSD1306_t * dev, int16_t GPIO_MOSI, int16_t GPIO_SCLK, int16_t GPIO_CS, int16_t GPIO_DC, int16_t GPIO_RESET); +bool spi_master_write_byte(spi_device_handle_t SPIHandle, const uint8_t* Data, size_t DataLength ); +bool spi_master_write_command(SSD1306_t * dev, uint8_t Command ); +bool spi_master_write_data(SSD1306_t * dev, const uint8_t* Data, size_t DataLength ); +void spi_init(SSD1306_t * dev, int width, int height); +void spi_display_image(SSD1306_t * dev, int page, int seg, uint8_t * images, int width); +void spi_contrast(SSD1306_t * dev, int contrast); +void spi_hardware_scroll(SSD1306_t * dev, ssd1306_scroll_type_t scroll); + +#ifdef __cplusplus +} +#endif + +#endif /* MAIN_SSD1306_H_ */ + diff --git a/components/ssd1306/ssd1306_i2c.c b/components/ssd1306/ssd1306_i2c.c new file mode 100644 index 0000000..fe2d821 --- /dev/null +++ b/components/ssd1306/ssd1306_i2c.c @@ -0,0 +1,253 @@ +#include + +#include "freertos/FreeRTOS.h" +#include "freertos/task.h" + +#include "driver/i2c.h" +#include "esp_log.h" + +#include "ssd1306.h" + +#define tag "SSD1306" + +#if CONFIG_I2C_PORT_0 +#define I2C_NUM I2C_NUM_0 +#elif CONFIG_I2C_PORT_1 +#define I2C_NUM I2C_NUM_1 +#else +#define I2C_NUM I2C_NUM_0 // if spi is selected +#endif + +#define I2C_MASTER_FREQ_HZ 400000 /*!< I2C clock of SSD1306 can run at 400 kHz max. */ + +void i2c_master_init(SSD1306_t * dev, int16_t sda, int16_t scl, int16_t reset) +{ + i2c_config_t i2c_config = { + .mode = I2C_MODE_MASTER, + .sda_io_num = sda, + .scl_io_num = scl, + .sda_pullup_en = GPIO_PULLUP_ENABLE, + .scl_pullup_en = GPIO_PULLUP_ENABLE, + .master.clk_speed = I2C_MASTER_FREQ_HZ + }; + ESP_ERROR_CHECK(i2c_param_config(I2C_NUM, &i2c_config)); + ESP_ERROR_CHECK(i2c_driver_install(I2C_NUM, I2C_MODE_MASTER, 0, 0, 0)); + + if (reset >= 0) { + //gpio_pad_select_gpio(reset); + gpio_reset_pin(reset); + gpio_set_direction(reset, GPIO_MODE_OUTPUT); + gpio_set_level(reset, 0); + vTaskDelay(50 / portTICK_PERIOD_MS); + gpio_set_level(reset, 1); + } + dev->_address = I2CAddress; + dev->_flip = false; +} + +void i2c_init(SSD1306_t * dev, int width, int height) { + dev->_width = width; + dev->_height = height; + dev->_pages = 8; + if (dev->_height == 32) dev->_pages = 4; + + i2c_cmd_handle_t cmd = i2c_cmd_link_create(); + + i2c_master_start(cmd); + i2c_master_write_byte(cmd, (dev->_address << 1) | I2C_MASTER_WRITE, true); + i2c_master_write_byte(cmd, OLED_CONTROL_BYTE_CMD_STREAM, true); + i2c_master_write_byte(cmd, OLED_CMD_DISPLAY_OFF, true); // AE + i2c_master_write_byte(cmd, OLED_CMD_SET_MUX_RATIO, true); // A8 + if (dev->_height == 64) i2c_master_write_byte(cmd, 0x3F, true); + if (dev->_height == 32) i2c_master_write_byte(cmd, 0x1F, true); + i2c_master_write_byte(cmd, OLED_CMD_SET_DISPLAY_OFFSET, true); // D3 + i2c_master_write_byte(cmd, 0x00, true); + //i2c_master_write_byte(cmd, OLED_CONTROL_BYTE_DATA_STREAM, true); // 40 + i2c_master_write_byte(cmd, OLED_CMD_SET_DISPLAY_START_LINE, true); // 40 + //i2c_master_write_byte(cmd, OLED_CMD_SET_SEGMENT_REMAP, true); // A1 + if (dev->_flip) { + i2c_master_write_byte(cmd, OLED_CMD_SET_SEGMENT_REMAP_0, true); // A0 + } else { + i2c_master_write_byte(cmd, OLED_CMD_SET_SEGMENT_REMAP_1, true); // A1 + } + i2c_master_write_byte(cmd, OLED_CMD_SET_COM_SCAN_MODE, true); // C8 + i2c_master_write_byte(cmd, OLED_CMD_SET_DISPLAY_CLK_DIV, true); // D5 + i2c_master_write_byte(cmd, 0x80, true); + i2c_master_write_byte(cmd, OLED_CMD_SET_COM_PIN_MAP, true); // DA + if (dev->_height == 64) i2c_master_write_byte(cmd, 0x12, true); + if (dev->_height == 32) i2c_master_write_byte(cmd, 0x02, true); + i2c_master_write_byte(cmd, OLED_CMD_SET_CONTRAST, true); // 81 + i2c_master_write_byte(cmd, 0xFF, true); + i2c_master_write_byte(cmd, OLED_CMD_DISPLAY_RAM, true); // A4 + i2c_master_write_byte(cmd, OLED_CMD_SET_VCOMH_DESELCT, true); // DB + i2c_master_write_byte(cmd, 0x40, true); + i2c_master_write_byte(cmd, OLED_CMD_SET_MEMORY_ADDR_MODE, true); // 20 + //i2c_master_write_byte(cmd, OLED_CMD_SET_HORI_ADDR_MODE, true); // 00 + i2c_master_write_byte(cmd, OLED_CMD_SET_PAGE_ADDR_MODE, true); // 02 + // Set Lower Column Start Address for Page Addressing Mode + i2c_master_write_byte(cmd, 0x00, true); + // Set Higher Column Start Address for Page Addressing Mode + i2c_master_write_byte(cmd, 0x10, true); + i2c_master_write_byte(cmd, OLED_CMD_SET_CHARGE_PUMP, true); // 8D + i2c_master_write_byte(cmd, 0x14, true); + i2c_master_write_byte(cmd, OLED_CMD_DEACTIVE_SCROLL, true); // 2E + i2c_master_write_byte(cmd, OLED_CMD_DISPLAY_NORMAL, true); // A6 + i2c_master_write_byte(cmd, OLED_CMD_DISPLAY_ON, true); // AF + + i2c_master_stop(cmd); + + esp_err_t espRc = i2c_master_cmd_begin(I2C_NUM, cmd, 10/portTICK_PERIOD_MS); + if (espRc == ESP_OK) { + ESP_LOGI(tag, "OLED configured successfully"); + } else { + ESP_LOGE(tag, "OLED configuration failed. code: 0x%.2X", espRc); + } + i2c_cmd_link_delete(cmd); +} + + +void i2c_display_image(SSD1306_t * dev, int page, int seg, uint8_t * images, int width) { + i2c_cmd_handle_t cmd; + + if (page >= dev->_pages) return; + if (seg >= dev->_width) return; + + int _seg = seg + CONFIG_OFFSETX; + uint8_t columLow = _seg & 0x0F; + uint8_t columHigh = (_seg >> 4) & 0x0F; + + int _page = page; + if (dev->_flip) { + _page = (dev->_pages - page) - 1; + } + + cmd = i2c_cmd_link_create(); + i2c_master_start(cmd); + i2c_master_write_byte(cmd, (dev->_address << 1) | I2C_MASTER_WRITE, true); + + i2c_master_write_byte(cmd, OLED_CONTROL_BYTE_CMD_STREAM, true); + // Set Lower Column Start Address for Page Addressing Mode + i2c_master_write_byte(cmd, (0x00 + columLow), true); + // Set Higher Column Start Address for Page Addressing Mode + i2c_master_write_byte(cmd, (0x10 + columHigh), true); + // Set Page Start Address for Page Addressing Mode + i2c_master_write_byte(cmd, 0xB0 | _page, true); + + i2c_master_stop(cmd); + i2c_master_cmd_begin(I2C_NUM, cmd, 10/portTICK_PERIOD_MS); + i2c_cmd_link_delete(cmd); + + cmd = i2c_cmd_link_create(); + i2c_master_start(cmd); + i2c_master_write_byte(cmd, (dev->_address << 1) | I2C_MASTER_WRITE, true); + + i2c_master_write_byte(cmd, OLED_CONTROL_BYTE_DATA_STREAM, true); + i2c_master_write(cmd, images, width, true); + + i2c_master_stop(cmd); + i2c_master_cmd_begin(I2C_NUM, cmd, 10/portTICK_PERIOD_MS); + i2c_cmd_link_delete(cmd); +} + +void i2c_contrast(SSD1306_t * dev, int contrast) { + i2c_cmd_handle_t cmd; + int _contrast = contrast; + if (contrast < 0x0) _contrast = 0; + if (contrast > 0xFF) _contrast = 0xFF; + + cmd = i2c_cmd_link_create(); + i2c_master_start(cmd); + i2c_master_write_byte(cmd, (dev->_address << 1) | I2C_MASTER_WRITE, true); + i2c_master_write_byte(cmd, OLED_CONTROL_BYTE_CMD_STREAM, true); + i2c_master_write_byte(cmd, OLED_CMD_SET_CONTRAST, true); // 81 + i2c_master_write_byte(cmd, _contrast, true); + i2c_master_stop(cmd); + i2c_master_cmd_begin(I2C_NUM, cmd, 10/portTICK_PERIOD_MS); + i2c_cmd_link_delete(cmd); +} + + +void i2c_hardware_scroll(SSD1306_t * dev, ssd1306_scroll_type_t scroll) { + esp_err_t espRc; + + i2c_cmd_handle_t cmd = i2c_cmd_link_create(); + i2c_master_start(cmd); + + i2c_master_write_byte(cmd, (dev->_address << 1) | I2C_MASTER_WRITE, true); + i2c_master_write_byte(cmd, OLED_CONTROL_BYTE_CMD_STREAM, true); + + if (scroll == SCROLL_RIGHT) { + i2c_master_write_byte(cmd, OLED_CMD_HORIZONTAL_RIGHT, true); // 26 + i2c_master_write_byte(cmd, 0x00, true); // Dummy byte + i2c_master_write_byte(cmd, 0x00, true); // Define start page address + i2c_master_write_byte(cmd, 0x07, true); // Frame frequency + i2c_master_write_byte(cmd, 0x07, true); // Define end page address + i2c_master_write_byte(cmd, 0x00, true); // + i2c_master_write_byte(cmd, 0xFF, true); // + i2c_master_write_byte(cmd, OLED_CMD_ACTIVE_SCROLL, true); // 2F + } + + if (scroll == SCROLL_LEFT) { + i2c_master_write_byte(cmd, OLED_CMD_HORIZONTAL_LEFT, true); // 27 + i2c_master_write_byte(cmd, 0x00, true); // Dummy byte + i2c_master_write_byte(cmd, 0x00, true); // Define start page address + i2c_master_write_byte(cmd, 0x07, true); // Frame frequency + i2c_master_write_byte(cmd, 0x07, true); // Define end page address + i2c_master_write_byte(cmd, 0x00, true); // + i2c_master_write_byte(cmd, 0xFF, true); // + i2c_master_write_byte(cmd, OLED_CMD_ACTIVE_SCROLL, true); // 2F + } + + if (scroll == SCROLL_DOWN) { + i2c_master_write_byte(cmd, OLED_CMD_CONTINUOUS_SCROLL, true); // 29 + i2c_master_write_byte(cmd, 0x00, true); // Dummy byte + i2c_master_write_byte(cmd, 0x00, true); // Define start page address + i2c_master_write_byte(cmd, 0x07, true); // Frame frequency + //i2c_master_write_byte(cmd, 0x01, true); // Define end page address + i2c_master_write_byte(cmd, 0x00, true); // Define end page address + i2c_master_write_byte(cmd, 0x3F, true); // Vertical scrolling offset + + i2c_master_write_byte(cmd, OLED_CMD_VERTICAL, true); // A3 + i2c_master_write_byte(cmd, 0x00, true); + if (dev->_height == 64) + //i2c_master_write_byte(cmd, 0x7F, true); + i2c_master_write_byte(cmd, 0x40, true); + if (dev->_height == 32) + i2c_master_write_byte(cmd, 0x20, true); + i2c_master_write_byte(cmd, OLED_CMD_ACTIVE_SCROLL, true); // 2F + } + + if (scroll == SCROLL_UP) { + i2c_master_write_byte(cmd, OLED_CMD_CONTINUOUS_SCROLL, true); // 29 + i2c_master_write_byte(cmd, 0x00, true); // Dummy byte + i2c_master_write_byte(cmd, 0x00, true); // Define start page address + i2c_master_write_byte(cmd, 0x07, true); // Frame frequency + //i2c_master_write_byte(cmd, 0x01, true); // Define end page address + i2c_master_write_byte(cmd, 0x00, true); // Define end page address + i2c_master_write_byte(cmd, 0x01, true); // Vertical scrolling offset + + i2c_master_write_byte(cmd, OLED_CMD_VERTICAL, true); // A3 + i2c_master_write_byte(cmd, 0x00, true); + if (dev->_height == 64) + //i2c_master_write_byte(cmd, 0x7F, true); + i2c_master_write_byte(cmd, 0x40, true); + if (dev->_height == 32) + i2c_master_write_byte(cmd, 0x20, true); + i2c_master_write_byte(cmd, OLED_CMD_ACTIVE_SCROLL, true); // 2F + } + + if (scroll == SCROLL_STOP) { + i2c_master_write_byte(cmd, OLED_CMD_DEACTIVE_SCROLL, true); // 2E + } + + i2c_master_stop(cmd); + espRc = i2c_master_cmd_begin(I2C_NUM, cmd, 10/portTICK_PERIOD_MS); + if (espRc == ESP_OK) { + ESP_LOGD(tag, "Scroll command succeeded"); + } else { + ESP_LOGE(tag, "Scroll command failed. code: 0x%.2X", espRc); + } + + i2c_cmd_link_delete(cmd); +} + diff --git a/components/ssd1306/ssd1306_spi.c b/components/ssd1306/ssd1306_spi.c new file mode 100644 index 0000000..fce2b7f --- /dev/null +++ b/components/ssd1306/ssd1306_spi.c @@ -0,0 +1,254 @@ +#include + +#include "freertos/FreeRTOS.h" +#include "freertos/task.h" + +#include "driver/spi_master.h" +#include "driver/gpio.h" +#include "esp_log.h" + +#include "ssd1306.h" + +#define TAG "SSD1306" + +#if CONFIG_SPI2_HOST +#define HOST_ID SPI2_HOST +#elif CONFIG_SPI3_HOST +#define HOST_ID SPI3_HOST +#else +#define HOST_ID SPI2_HOST // If i2c is selected +#endif + +static const int SPI_Command_Mode = 0; +static const int SPI_Data_Mode = 1; +static const int SPI_Frequency = 1000000; // 1MHz + +void spi_master_init(SSD1306_t * dev, int16_t GPIO_MOSI, int16_t GPIO_SCLK, int16_t GPIO_CS, int16_t GPIO_DC, int16_t GPIO_RESET) +{ + esp_err_t ret; + + //gpio_pad_select_gpio( GPIO_CS ); + gpio_reset_pin( GPIO_CS ); + gpio_set_direction( GPIO_CS, GPIO_MODE_OUTPUT ); + gpio_set_level( GPIO_CS, 0 ); + + //gpio_pad_select_gpio( GPIO_DC ); + gpio_reset_pin( GPIO_DC ); + gpio_set_direction( GPIO_DC, GPIO_MODE_OUTPUT ); + gpio_set_level( GPIO_DC, 0 ); + + if ( GPIO_RESET >= 0 ) { + //gpio_pad_select_gpio( GPIO_RESET ); + gpio_reset_pin( GPIO_RESET ); + gpio_set_direction( GPIO_RESET, GPIO_MODE_OUTPUT ); + gpio_set_level( GPIO_RESET, 0 ); + vTaskDelay( pdMS_TO_TICKS( 100 ) ); + gpio_set_level( GPIO_RESET, 1 ); + } + + spi_bus_config_t spi_bus_config = { + .mosi_io_num = GPIO_MOSI, + .miso_io_num = -1, + .sclk_io_num = GPIO_SCLK, + .quadwp_io_num = -1, + .quadhd_io_num = -1, + .max_transfer_sz = 0, + .flags = 0 + }; + + ESP_LOGI(TAG, "SPI HOST_ID=%d", HOST_ID); + ret = spi_bus_initialize( HOST_ID, &spi_bus_config, SPI_DMA_CH_AUTO ); + ESP_LOGI(TAG, "spi_bus_initialize=%d",ret); + assert(ret==ESP_OK); + + spi_device_interface_config_t devcfg; + memset( &devcfg, 0, sizeof( spi_device_interface_config_t ) ); + devcfg.clock_speed_hz = SPI_Frequency; + devcfg.spics_io_num = GPIO_CS; + devcfg.queue_size = 1; + + spi_device_handle_t handle; + ret = spi_bus_add_device( HOST_ID, &devcfg, &handle); + ESP_LOGI(TAG, "spi_bus_add_device=%d",ret); + assert(ret==ESP_OK); + dev->_dc = GPIO_DC; + dev->_SPIHandle = handle; + dev->_address = SPIAddress; + dev->_flip = false; +} + + +bool spi_master_write_byte(spi_device_handle_t SPIHandle, const uint8_t* Data, size_t DataLength ) +{ + spi_transaction_t SPITransaction; + + if ( DataLength > 0 ) { + memset( &SPITransaction, 0, sizeof( spi_transaction_t ) ); + SPITransaction.length = DataLength * 8; + SPITransaction.tx_buffer = Data; + spi_device_transmit( SPIHandle, &SPITransaction ); + } + + return true; +} + +bool spi_master_write_command(SSD1306_t * dev, uint8_t Command ) +{ + static uint8_t CommandByte = 0; + CommandByte = Command; + gpio_set_level( dev->_dc, SPI_Command_Mode ); + return spi_master_write_byte( dev->_SPIHandle, &CommandByte, 1 ); +} + +bool spi_master_write_data(SSD1306_t * dev, const uint8_t* Data, size_t DataLength ) +{ + gpio_set_level( dev->_dc, SPI_Data_Mode ); + return spi_master_write_byte( dev->_SPIHandle, Data, DataLength ); +} + + +void spi_init(SSD1306_t * dev, int width, int height) +{ + dev->_width = width; + dev->_height = height; + dev->_pages = 8; + if (dev->_height == 32) dev->_pages = 4; + + spi_master_write_command(dev, OLED_CMD_DISPLAY_OFF); // AE + spi_master_write_command(dev, OLED_CMD_SET_MUX_RATIO); // A8 + if (dev->_height == 64) spi_master_write_command(dev, 0x3F); + if (dev->_height == 32) spi_master_write_command(dev, 0x1F); + spi_master_write_command(dev, OLED_CMD_SET_DISPLAY_OFFSET); // D3 + spi_master_write_command(dev, 0x00); + spi_master_write_command(dev, OLED_CONTROL_BYTE_DATA_STREAM); // 40 + if (dev->_flip) { + spi_master_write_command(dev, OLED_CMD_SET_SEGMENT_REMAP_0); // A0 + } else { + spi_master_write_command(dev, OLED_CMD_SET_SEGMENT_REMAP_1); // A1 + } + //spi_master_write_command(dev, OLED_CMD_SET_SEGMENT_REMAP); // A1 + spi_master_write_command(dev, OLED_CMD_SET_COM_SCAN_MODE); // C8 + spi_master_write_command(dev, OLED_CMD_SET_DISPLAY_CLK_DIV); // D5 + spi_master_write_command(dev, 0x80); + spi_master_write_command(dev, OLED_CMD_SET_COM_PIN_MAP); // DA + if (dev->_height == 64) spi_master_write_command(dev, 0x12); + if (dev->_height == 32) spi_master_write_command(dev, 0x02); + spi_master_write_command(dev, OLED_CMD_SET_CONTRAST); // 81 + spi_master_write_command(dev, 0xFF); + spi_master_write_command(dev, OLED_CMD_DISPLAY_RAM); // A4 + spi_master_write_command(dev, OLED_CMD_SET_VCOMH_DESELCT); // DB + spi_master_write_command(dev, 0x40); + spi_master_write_command(dev, OLED_CMD_SET_MEMORY_ADDR_MODE); // 20 + //spi_master_write_command(dev, OLED_CMD_SET_HORI_ADDR_MODE); // 00 + spi_master_write_command(dev, OLED_CMD_SET_PAGE_ADDR_MODE); // 02 + // Set Lower Column Start Address for Page Addressing Mode + spi_master_write_command(dev, 0x00); + // Set Higher Column Start Address for Page Addressing Mode + spi_master_write_command(dev, 0x10); + spi_master_write_command(dev, OLED_CMD_SET_CHARGE_PUMP); // 8D + spi_master_write_command(dev, 0x14); + spi_master_write_command(dev, OLED_CMD_DEACTIVE_SCROLL); // 2E + spi_master_write_command(dev, OLED_CMD_DISPLAY_NORMAL); // A6 + spi_master_write_command(dev, OLED_CMD_DISPLAY_ON); // AF +} + + +void spi_display_image(SSD1306_t * dev, int page, int seg, uint8_t * images, int width) +{ + if (page >= dev->_pages) return; + if (seg >= dev->_width) return; + + int _seg = seg + CONFIG_OFFSETX; + uint8_t columLow = _seg & 0x0F; + uint8_t columHigh = (_seg >> 4) & 0x0F; + + int _page = page; + if (dev->_flip) { + _page = (dev->_pages - page) - 1; + } + + // Set Lower Column Start Address for Page Addressing Mode + spi_master_write_command(dev, (0x00 + columLow)); + // Set Higher Column Start Address for Page Addressing Mode + spi_master_write_command(dev, (0x10 + columHigh)); + // Set Page Start Address for Page Addressing Mode + spi_master_write_command(dev, 0xB0 | _page); + + spi_master_write_data(dev, images, width); + +} + +void spi_contrast(SSD1306_t * dev, int contrast) { + int _contrast = contrast; + if (contrast < 0x0) _contrast = 0; + if (contrast > 0xFF) _contrast = 0xFF; + + spi_master_write_command(dev, OLED_CMD_SET_CONTRAST); // 81 + spi_master_write_command(dev, _contrast); +} + +void spi_hardware_scroll(SSD1306_t * dev, ssd1306_scroll_type_t scroll) +{ + + if (scroll == SCROLL_RIGHT) { + spi_master_write_command(dev, OLED_CMD_HORIZONTAL_RIGHT); // 26 + spi_master_write_command(dev, 0x00); // Dummy byte + spi_master_write_command(dev, 0x00); // Define start page address + spi_master_write_command(dev, 0x07); // Frame frequency + spi_master_write_command(dev, 0x07); // Define end page address + spi_master_write_command(dev, 0x00); // + spi_master_write_command(dev, 0xFF); // + spi_master_write_command(dev, OLED_CMD_ACTIVE_SCROLL); // 2F + } + + if (scroll == SCROLL_LEFT) { + spi_master_write_command(dev, OLED_CMD_HORIZONTAL_LEFT); // 27 + spi_master_write_command(dev, 0x00); // Dummy byte + spi_master_write_command(dev, 0x00); // Define start page address + spi_master_write_command(dev, 0x07); // Frame frequency + spi_master_write_command(dev, 0x07); // Define end page address + spi_master_write_command(dev, 0x00); // + spi_master_write_command(dev, 0xFF); // + spi_master_write_command(dev, OLED_CMD_ACTIVE_SCROLL); // 2F + } + + if (scroll == SCROLL_DOWN) { + spi_master_write_command(dev, OLED_CMD_CONTINUOUS_SCROLL); // 29 + spi_master_write_command(dev, 0x00); // Dummy byte + spi_master_write_command(dev, 0x00); // Define start page address + spi_master_write_command(dev, 0x07); // Frame frequency + //spi_master_write_command(dev, 0x01); // Define end page address + spi_master_write_command(dev, 0x00); // Define end page address + spi_master_write_command(dev, 0x3F); // Vertical scrolling offset + + spi_master_write_command(dev, OLED_CMD_VERTICAL); // A3 + spi_master_write_command(dev, 0x00); + if (dev->_height == 64) + spi_master_write_command(dev, 0x40); + if (dev->_height == 32) + spi_master_write_command(dev, 0x20); + spi_master_write_command(dev, OLED_CMD_ACTIVE_SCROLL); // 2F + } + + if (scroll == SCROLL_UP) { + spi_master_write_command(dev, OLED_CMD_CONTINUOUS_SCROLL); // 29 + spi_master_write_command(dev, 0x00); // Dummy byte + spi_master_write_command(dev, 0x00); // Define start page address + spi_master_write_command(dev, 0x07); // Frame frequency + //spi_master_write_command(dev, 0x01); // Define end page address + spi_master_write_command(dev, 0x00); // Define end page address + spi_master_write_command(dev, 0x01); // Vertical scrolling offset + + spi_master_write_command(dev, OLED_CMD_VERTICAL); // A3 + spi_master_write_command(dev, 0x00); + if (dev->_height == 64) + spi_master_write_command(dev, 0x40); + if (dev->_height == 32) + spi_master_write_command(dev, 0x20); + spi_master_write_command(dev, OLED_CMD_ACTIVE_SCROLL); // 2F + } + + if (scroll == SCROLL_STOP) { + spi_master_write_command(dev, OLED_CMD_DEACTIVE_SCROLL); // 2E + } +} diff --git a/connection-plan.drawio.pdf b/connection-plan.drawio.pdf index 3fa53fc..51456ac 100644 Binary files a/connection-plan.drawio.pdf and b/connection-plan.drawio.pdf differ diff --git a/board_control/react-app/package-lock.json b/react-app/package-lock.json similarity index 100% rename from board_control/react-app/package-lock.json rename to react-app/package-lock.json diff --git a/board_control/react-app/package.json b/react-app/package.json similarity index 100% rename from board_control/react-app/package.json rename to react-app/package.json diff --git a/board_control/react-app/public/index.html b/react-app/public/index.html similarity index 100% rename from board_control/react-app/public/index.html rename to react-app/public/index.html diff --git a/board_control/react-app/src/App.js b/react-app/src/App.js similarity index 100% rename from board_control/react-app/src/App.js rename to react-app/src/App.js diff --git a/board_control/react-app/src/index.js b/react-app/src/index.js similarity index 100% rename from board_control/react-app/src/index.js rename to react-app/src/index.js