Compare commits
33 Commits
encoder-te
...
V1.0
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
5a3c6b15bc | ||
|
|
248668c526 | ||
|
|
9d416d29e6 | ||
|
|
070fd7069d | ||
|
|
c1a12d93f0 | ||
|
|
92f7299080 | ||
|
|
2e331d841d | ||
|
|
9f329101a1 | ||
|
|
4e2cc070d1 | ||
|
|
586c335896 | ||
|
|
6acf99d894 | ||
|
|
9665560bbb | ||
|
|
c8ffd94fe9 | ||
|
|
c5438b6c4c | ||
|
|
01c5db39c1 | ||
|
|
b238e582cc | ||
|
|
ae41b93e63 | ||
|
|
5ddf8699e2 | ||
|
|
8900da9113 | ||
|
|
68f97644be | ||
|
|
e9e1df9ea1 | ||
|
|
dddd54b03a | ||
|
|
f6b2093650 | ||
|
|
68dc012fcc | ||
|
|
8b9b5ff736 | ||
|
|
0aea494783 | ||
|
|
7ccde65893 | ||
|
|
59bb48902d | ||
|
|
b68dae7e59 | ||
|
|
7fae539f14 | ||
|
|
22f8aef8d2 | ||
|
|
739f5ef4c2 | ||
|
|
a3f3cb340c |
3
.gitignore
vendored
3
.gitignore
vendored
@@ -4,3 +4,6 @@ build
|
||||
# VIM files
|
||||
*.swp
|
||||
*.swo
|
||||
|
||||
# drawio files
|
||||
*.bkp
|
||||
|
||||
18
README.md
Normal file
18
README.md
Normal file
@@ -0,0 +1,18 @@
|
||||
# Hardware
|
||||
## connection plan
|
||||
See [connection-plan.pdf](connection-plan.pdf)
|
||||
|
||||
|
||||
# Components
|
||||
## rotary encoder LPD3806-600BM-G5-24C
|
||||
- Pulses: 600 p/r (Single-phase 600 pulses /R,Two phase 4 frequency doubling to 2400 pulses)
|
||||
- Power source: DC5-24V
|
||||
- Shaft: 6*13mm/0.23*0.51"
|
||||
- Size: 38*35.5mm/1.49*1.39"
|
||||
- Output :AB 2phase output rectangular orthogonal pulse circuit, the output for the NPN open collector output type
|
||||
- Maximum mechanical speed: 5000 R / min
|
||||
- Response frequency: 0-20KHz
|
||||
- Cable length: 1.5 meter
|
||||
- size: http://domoticx.com/wp-content/uploads/2020/05/LPD3806-afmetingen.jpg
|
||||
- Wires: Green = A phase, white = B phase, red = Vcc power +, black = V0
|
||||
|
||||
4
components/gpio/CMakeLists.txt
Normal file
4
components/gpio/CMakeLists.txt
Normal file
@@ -0,0 +1,4 @@
|
||||
idf_component_register(
|
||||
SRCS "gpio_evaluateSwitch.cpp"
|
||||
INCLUDE_DIRS "."
|
||||
)
|
||||
171
components/gpio/gpio_evaluateSwitch.cpp
Normal file
171
components/gpio/gpio_evaluateSwitch.cpp
Normal file
@@ -0,0 +1,171 @@
|
||||
#include "gpio_evaluateSwitch.hpp"
|
||||
|
||||
static const char *TAG = "evaluateSwitch";
|
||||
|
||||
|
||||
gpio_evaluatedSwitch::gpio_evaluatedSwitch( //minimal (use default values)
|
||||
gpio_num_t gpio_num_declare
|
||||
){
|
||||
gpio_num = gpio_num_declare;
|
||||
pullup = true;
|
||||
inverted = false;
|
||||
|
||||
init();
|
||||
};
|
||||
|
||||
|
||||
|
||||
gpio_evaluatedSwitch::gpio_evaluatedSwitch( //optional parameters given
|
||||
gpio_num_t gpio_num_declare,
|
||||
bool pullup_declare,
|
||||
bool inverted_declare
|
||||
){
|
||||
gpio_num = gpio_num_declare;
|
||||
pullup = pullup_declare;
|
||||
inverted = inverted_declare;
|
||||
|
||||
init();
|
||||
};
|
||||
|
||||
|
||||
|
||||
void gpio_evaluatedSwitch::init(){
|
||||
ESP_LOGI(TAG, "initializing gpio pin %d", (int)gpio_num);
|
||||
|
||||
//define gpio pin as input
|
||||
gpio_pad_select_gpio(gpio_num);
|
||||
gpio_set_direction(gpio_num, GPIO_MODE_INPUT);
|
||||
|
||||
if (pullup == true){ //enable pullup if desired (default)
|
||||
gpio_pad_select_gpio(gpio_num);
|
||||
gpio_set_pull_mode(gpio_num, GPIO_PULLUP_ONLY);
|
||||
}else{
|
||||
gpio_set_pull_mode(gpio_num, GPIO_FLOATING);
|
||||
gpio_pad_select_gpio(gpio_num);
|
||||
}
|
||||
//TODO add pulldown option
|
||||
//gpio_set_pull_mode(gpio_num, GPIO_PULLDOWN_ONLY);
|
||||
};
|
||||
|
||||
|
||||
void gpio_evaluatedSwitch::handle(){ //Statemachine for debouncing and edge detection
|
||||
if (inverted == true){
|
||||
//=========================================================
|
||||
//=========== Statemachine for inverted switch ============
|
||||
//=================== (switch to VCC) =====================
|
||||
//=========================================================
|
||||
switch (p_state){
|
||||
default:
|
||||
p_state = switchState::FALSE;
|
||||
break;
|
||||
|
||||
case switchState::FALSE: //input confirmed high (released)
|
||||
fallingEdge = false; //reset edge event
|
||||
if (gpio_get_level(gpio_num) == 1){ //pin high (on)
|
||||
p_state = switchState::HIGH;
|
||||
timestampHigh = esp_log_timestamp(); //save timestamp switched from low to high
|
||||
} else {
|
||||
msReleased = esp_log_timestamp() - timestampLow; //update duration released
|
||||
}
|
||||
break;
|
||||
|
||||
case switchState::HIGH: //input recently switched to high (pressed)
|
||||
if (gpio_get_level(gpio_num) == 1){ //pin still high (on)
|
||||
if (esp_log_timestamp() - timestampHigh > minOnMs){ //pin in same state long enough
|
||||
p_state = switchState::TRUE;
|
||||
state = true;
|
||||
risingEdge = true;
|
||||
msReleased = timestampHigh - timestampLow; //calculate duration the button was released
|
||||
}
|
||||
}else{
|
||||
p_state = switchState::FALSE;
|
||||
}
|
||||
break;
|
||||
|
||||
case switchState::TRUE: //input confirmed high (pressed)
|
||||
risingEdge = false; //reset edge event
|
||||
if (gpio_get_level(gpio_num) == 0){ //pin low (off)
|
||||
timestampLow = esp_log_timestamp();
|
||||
p_state = switchState::LOW;
|
||||
} else {
|
||||
msPressed = esp_log_timestamp() - timestampHigh; //update duration pressed
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case switchState::LOW: //input recently switched to low (released)
|
||||
if (gpio_get_level(gpio_num) == 0){ //pin still low (off)
|
||||
if (esp_log_timestamp() - timestampLow > minOffMs){ //pin in same state long enough
|
||||
p_state = switchState::FALSE;
|
||||
msPressed = timestampLow - timestampHigh; //calculate duration the button was pressed
|
||||
state=false;
|
||||
fallingEdge=true;
|
||||
}
|
||||
}else{
|
||||
p_state = switchState::TRUE;
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
}else{
|
||||
//=========================================================
|
||||
//========= Statemachine for not inverted switch ==========
|
||||
//=================== (switch to GND) =====================
|
||||
//=========================================================
|
||||
switch (p_state){
|
||||
default:
|
||||
p_state = switchState::FALSE;
|
||||
break;
|
||||
|
||||
case switchState::FALSE: //input confirmed high (released)
|
||||
fallingEdge = false; //reset edge event
|
||||
if (gpio_get_level(gpio_num) == 0){ //pin low (on)
|
||||
p_state = switchState::LOW;
|
||||
timestampLow = esp_log_timestamp(); //save timestamp switched from high to low
|
||||
} else {
|
||||
msReleased = esp_log_timestamp() - timestampHigh; //update duration released
|
||||
}
|
||||
break;
|
||||
|
||||
case switchState::LOW: //input recently switched to low (pressed)
|
||||
if (gpio_get_level(gpio_num) == 0){ //pin still low (on)
|
||||
if (esp_log_timestamp() - timestampLow > minOnMs){ //pin in same state long enough
|
||||
p_state = switchState::TRUE;
|
||||
state = true;
|
||||
risingEdge = true;
|
||||
msReleased = timestampLow - timestampHigh; //calculate duration the button was released
|
||||
}
|
||||
}else{
|
||||
p_state = switchState::FALSE;
|
||||
}
|
||||
break;
|
||||
|
||||
case switchState::TRUE: //input confirmed low (pressed)
|
||||
risingEdge = false; //reset edge event
|
||||
if (gpio_get_level(gpio_num) == 1){ //pin high (off)
|
||||
timestampHigh = esp_log_timestamp();
|
||||
p_state = switchState::HIGH;
|
||||
} else {
|
||||
msPressed = esp_log_timestamp() - timestampLow; //update duration pressed
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case switchState::HIGH: //input recently switched to high (released)
|
||||
if (gpio_get_level(gpio_num) == 1){ //pin still high (off)
|
||||
if (esp_log_timestamp() - timestampHigh > minOffMs){ //pin in same state long enough
|
||||
p_state = switchState::FALSE;
|
||||
msPressed = timestampHigh - timestampLow; //calculate duration the button was pressed
|
||||
state=false;
|
||||
fallingEdge=true;
|
||||
}
|
||||
}else{
|
||||
p_state = switchState::TRUE;
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
59
components/gpio/gpio_evaluateSwitch.hpp
Normal file
59
components/gpio/gpio_evaluateSwitch.hpp
Normal file
@@ -0,0 +1,59 @@
|
||||
#pragma once
|
||||
|
||||
#include <stdio.h>
|
||||
|
||||
extern "C"
|
||||
{
|
||||
#include "freertos/FreeRTOS.h"
|
||||
#include "freertos/task.h"
|
||||
#include "driver/gpio.h"
|
||||
#include "esp_log.h"
|
||||
}
|
||||
|
||||
//constructor examples:
|
||||
//switch to gnd and us internal pullup:
|
||||
//gpio_evaluatedSwitch s3(GPIO_NUM_14);
|
||||
//switch to gnd dont use internal pullup:
|
||||
//gpio_evaluatedSwitch s3(GPIO_NUM_14 false);
|
||||
//switch to VCC (inverted) and dont use internal pullup:
|
||||
//gpio_evaluatedSwitch s3(GPIO_NUM_14 false, true);
|
||||
|
||||
|
||||
class gpio_evaluatedSwitch {
|
||||
public:
|
||||
//--- input ---
|
||||
uint32_t minOnMs = 30;
|
||||
uint32_t minOffMs = 30;
|
||||
gpio_evaluatedSwitch( //constructor minimal (default parameters pullup=true, inverted=false)
|
||||
gpio_num_t gpio_num_declare
|
||||
);
|
||||
gpio_evaluatedSwitch( //constructor with optional parameters
|
||||
gpio_num_t gpio_num_declare,
|
||||
bool pullup_declare,
|
||||
bool inverted_declare=false
|
||||
);
|
||||
|
||||
//--- output --- TODO make readonly? (e.g. public section: const int& x = m_x;)
|
||||
bool state = false;
|
||||
bool risingEdge = false;
|
||||
bool fallingEdge = false;
|
||||
uint32_t msPressed = 0;
|
||||
uint32_t msReleased = 0;
|
||||
|
||||
//--- functions ---
|
||||
void handle(); //Statemachine for debouncing and edge detection
|
||||
|
||||
private:
|
||||
gpio_num_t gpio_num;
|
||||
bool pullup;
|
||||
bool inverted;
|
||||
|
||||
enum class switchState {TRUE, FALSE, LOW, HIGH};
|
||||
switchState p_state = switchState::FALSE;
|
||||
uint32_t timestampLow = 0;
|
||||
uint32_t timestampHigh = 0;
|
||||
void init();
|
||||
|
||||
};
|
||||
|
||||
|
||||
@@ -236,7 +236,7 @@ esp_err_t max7219_draw_text_7seg(max7219_t *dev, uint8_t pos, const char *s)
|
||||
{
|
||||
CHECK_ARG(dev && s);
|
||||
|
||||
while (s && pos < dev->digits)
|
||||
while (*s != '\0' && pos < dev->digits)
|
||||
{
|
||||
uint8_t c = get_char(dev, *s);
|
||||
if (*(s + 1) == '.')
|
||||
|
||||
1
connection-plan.drawio
Normal file
1
connection-plan.drawio
Normal file
File diff suppressed because one or more lines are too long
BIN
connection-plan.drawio.pdf
Normal file
BIN
connection-plan.drawio.pdf
Normal file
Binary file not shown.
1
function-diagram.drawio
Normal file
1
function-diagram.drawio
Normal file
File diff suppressed because one or more lines are too long
BIN
function-diagram.drawio.pdf
Normal file
BIN
function-diagram.drawio.pdf
Normal file
Binary file not shown.
@@ -1,2 +1,11 @@
|
||||
idf_component_register(SRCS "main.c"
|
||||
INCLUDE_DIRS ".")
|
||||
idf_component_register(
|
||||
SRCS
|
||||
"main.cpp"
|
||||
"config.cpp"
|
||||
"control.cpp"
|
||||
"buzzer.cpp"
|
||||
"vfd.cpp"
|
||||
"display.cpp"
|
||||
INCLUDE_DIRS
|
||||
"."
|
||||
)
|
||||
|
||||
98
main/buzzer.cpp
Normal file
98
main/buzzer.cpp
Normal file
@@ -0,0 +1,98 @@
|
||||
#include "buzzer.hpp"
|
||||
#include "config.hpp"
|
||||
|
||||
static const char *TAG_BUZZER = "buzzer";
|
||||
|
||||
//============================
|
||||
//========== init ============
|
||||
//============================
|
||||
//define gpio pin as output, initialize queue
|
||||
void buzzer_t::init(){
|
||||
//define buzzer pin as output
|
||||
gpio_pad_select_gpio(gpio_pin);
|
||||
gpio_set_direction(gpio_pin, GPIO_MODE_OUTPUT);
|
||||
//create queue
|
||||
beepQueue = xQueueCreate( 20, sizeof( struct beepEntry ) );
|
||||
}
|
||||
|
||||
|
||||
//=============================
|
||||
//======== constructor ========
|
||||
//=============================
|
||||
//copy provided config parameters to private variables, run init function
|
||||
buzzer_t::buzzer_t(gpio_num_t gpio_pin_f, uint16_t msGap_f){
|
||||
ESP_LOGI(TAG_BUZZER, "Initializing buzzer");
|
||||
//copy configuration parameters to variables
|
||||
gpio_pin = gpio_pin_f;
|
||||
msGap = msGap_f;
|
||||
//run init function to initialize gpio and queue
|
||||
init();
|
||||
};
|
||||
|
||||
|
||||
//============================
|
||||
//=========== beep ===========
|
||||
//============================
|
||||
//function to add a beep command to the queue
|
||||
void buzzer_t::beep(uint8_t count, uint16_t msOn, uint16_t msOff, bool noGap){
|
||||
//create entry struct with provided data
|
||||
struct beepEntry entryInsert = {
|
||||
count = count,
|
||||
msOn = msOn,
|
||||
msOff = msOff,
|
||||
noGap = noGap
|
||||
};
|
||||
|
||||
// Send a pointer to a struct AMessage object. Don't block if the
|
||||
// queue is already full.
|
||||
//struct beepEntry *entryInsertPointer;
|
||||
//entryInsertPointer = &entryInsertData;
|
||||
ESP_LOGW(TAG_BUZZER, "Inserted object to queue - count=%d, msOn=%d, msOff=%d", entryInsert.count, entryInsert.msOn, entryInsert.msOff);
|
||||
//xQueueGenericSend( beepQueue, ( void * ) &entryInsertPointer, ( TickType_t ) 0, queueSEND_TO_BACK );
|
||||
xQueueSend( beepQueue, ( void * )&entryInsert, ( TickType_t ) 0 );
|
||||
}
|
||||
|
||||
|
||||
//==============================
|
||||
//======== processQueue ========
|
||||
//==============================
|
||||
void buzzer_t::processQueue(){
|
||||
//struct for receiving incomming events
|
||||
struct beepEntry entryRead = { };
|
||||
|
||||
//loop forever
|
||||
while(1){
|
||||
ESP_LOGD(TAG_BUZZER, "processQueue: waiting for beep command");
|
||||
|
||||
//if queue is ready
|
||||
if( beepQueue != 0 )
|
||||
{
|
||||
// wait for a queue entry to be available indefinetely if INCLUDE_vTaskSuspend is enabled in the FreeRTOS config
|
||||
// otherwise waits for at least 7 weeks
|
||||
if( xQueueReceive( beepQueue, &entryRead, portMAX_DELAY ) )
|
||||
{
|
||||
ESP_LOGW(TAG_BUZZER, "Read entry from queue: count=%d, msOn=%d, msOff=%d", entryRead.count, entryRead.msOn, entryRead.msOff);
|
||||
|
||||
//beep requested count with requested delays
|
||||
for (int i = entryRead.count; i--;){
|
||||
//turn on
|
||||
ESP_LOGD(TAG_BUZZER, "turning buzzer on");
|
||||
gpio_set_level(gpio_pin, 1);
|
||||
vTaskDelay(entryRead.msOn / portTICK_PERIOD_MS);
|
||||
//turn off
|
||||
ESP_LOGD(TAG_BUZZER, "turning buzzer off");
|
||||
gpio_set_level(gpio_pin, 0);
|
||||
vTaskDelay(entryRead.msOff / portTICK_PERIOD_MS);
|
||||
}
|
||||
if( entryRead.noGap == false ){
|
||||
//wait for minimum gap between beep events
|
||||
vTaskDelay(msGap / portTICK_PERIOD_MS);
|
||||
}
|
||||
}
|
||||
}else{ //wait for queue to become available
|
||||
vTaskDelay(50 / portTICK_PERIOD_MS);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
57
main/buzzer.hpp
Normal file
57
main/buzzer.hpp
Normal file
@@ -0,0 +1,57 @@
|
||||
#pragma once
|
||||
|
||||
#include <stdio.h>
|
||||
|
||||
extern "C"
|
||||
{
|
||||
#include "freertos/FreeRTOS.h"
|
||||
#include "freertos/task.h"
|
||||
#include "driver/gpio.h"
|
||||
#include "esp_log.h"
|
||||
}
|
||||
|
||||
#include "freertos/queue.h"
|
||||
|
||||
|
||||
|
||||
//===================================
|
||||
//========= buzzer_t class ==========
|
||||
//===================================
|
||||
//class which blinks a gpio pin for the provided count and durations.
|
||||
//- 'processQueue' has to be run in a separate task
|
||||
//- uses a queue to queue up multiple beep commands
|
||||
class buzzer_t {
|
||||
public:
|
||||
//--- constructor ---
|
||||
buzzer_t(gpio_num_t gpio_pin_f, uint16_t msGap_f = 200);
|
||||
|
||||
//--- functions ---
|
||||
void processQueue(); //has to be run once in a separate task, waits for and processes queued events
|
||||
void beep(uint8_t count, uint16_t msOn, uint16_t msOff, bool noGap = false);
|
||||
//void clear(); (TODO - not implemented yet)
|
||||
//void createTask(); (TODO - not implemented yet)
|
||||
|
||||
//--- variables ---
|
||||
uint16_t msGap; //gap between beep entries (when multiple queued)
|
||||
|
||||
private:
|
||||
//--- functions ---
|
||||
void init();
|
||||
|
||||
//--- variables ---
|
||||
gpio_num_t gpio_pin;
|
||||
|
||||
struct beepEntry {
|
||||
uint8_t count;
|
||||
uint16_t msOn;
|
||||
uint16_t msOff;
|
||||
bool noGap;
|
||||
};
|
||||
|
||||
//queue for queueing up multiple events while one is still processing
|
||||
QueueHandle_t beepQueue = NULL;
|
||||
|
||||
};
|
||||
|
||||
|
||||
|
||||
15
main/config.cpp
Normal file
15
main/config.cpp
Normal file
@@ -0,0 +1,15 @@
|
||||
#include "config.hpp"
|
||||
|
||||
|
||||
//--- inputs ---
|
||||
//create and configure objects for evaluated switches
|
||||
gpio_evaluatedSwitch SW_START(GPIO_SW_START, true, false); //pullup true, not inverted (switch to GND, internal pullup used)
|
||||
gpio_evaluatedSwitch SW_RESET(GPIO_SW_RESET, true, false); //pullup true, not inverted (switch to GND, internal pullup used)
|
||||
gpio_evaluatedSwitch SW_SET(GPIO_SW_SET, true, false); //pullup true, not inverted (switch to GND, internal pullup used)
|
||||
gpio_evaluatedSwitch SW_PRESET1(GPIO_SW_PRESET1, true, false); //pullup true, not inverted (switch to GND, internal pullup used)
|
||||
gpio_evaluatedSwitch SW_PRESET2(GPIO_SW_PRESET2, false, true); //pullup false, INVERTED (switch to 3V3, pulldown on pcb soldered)
|
||||
gpio_evaluatedSwitch SW_PRESET3(GPIO_SW_PRESET3, false, true); //pullup false, INVERTED (switch to 3V3, pulldown on pcb soldered)
|
||||
|
||||
|
||||
//create buzzer object with no gap between beep events
|
||||
buzzer_t buzzer(GPIO_BUZZER, 0);
|
||||
84
main/config.hpp
Normal file
84
main/config.hpp
Normal file
@@ -0,0 +1,84 @@
|
||||
#pragma once
|
||||
extern "C" {
|
||||
#include "driver/adc.h"
|
||||
}
|
||||
#include "gpio_evaluateSwitch.hpp"
|
||||
#include "buzzer.hpp"
|
||||
|
||||
|
||||
//===================================
|
||||
//===== define output gpio pins =====
|
||||
//===================================
|
||||
//4x stepper mosfet outputs for VFD
|
||||
#define GPIO_VFD_FWD GPIO_NUM_4 //ST4
|
||||
#define GPIO_VFD_REV GPIO_NUM_16 //ST3
|
||||
#define GPIO_VFD_D0 GPIO_NUM_2 //ST2
|
||||
#define GPIO_VFD_D1 GPIO_NUM_15 //ST1
|
||||
//#define GPIO_VFD_D2 GPIO_NUM_15 //ST1 (D2 only used with 7.5kw vfd)
|
||||
|
||||
#define GPIO_MOS2 GPIO_NUM_5 //mos2
|
||||
#define GPIO_RELAY GPIO_NUM_13
|
||||
#define GPIO_BUZZER GPIO_NUM_12
|
||||
|
||||
|
||||
//==================================
|
||||
//===== define input gpio pins =====
|
||||
//==================================
|
||||
#define GPIO_SW_START GPIO_NUM_26
|
||||
#define GPIO_SW_RESET GPIO_NUM_25
|
||||
#define GPIO_SW_SET GPIO_NUM_33
|
||||
#define GPIO_SW_PRESET1 GPIO_NUM_32
|
||||
#define GPIO_SW_PRESET2 GPIO_NUM_34
|
||||
#define GPIO_SW_PRESET3 GPIO_NUM_39
|
||||
|
||||
#define GPIO_POTI GPIO_NUM_36
|
||||
#define ADC_CHANNEL_POTI ADC1_CHANNEL_0
|
||||
|
||||
|
||||
//--------------------------
|
||||
//----- display config -----
|
||||
//--------------------------
|
||||
#if ESP_IDF_VERSION < ESP_IDF_VERSION_VAL(4, 0, 0)
|
||||
#define HOST HSPI_HOST
|
||||
#else
|
||||
#define HOST SPI2_HOST
|
||||
#endif
|
||||
#define DISPLAY_PIN_NUM_MOSI GPIO_NUM_23
|
||||
#define DISPLAY_PIN_NUM_CLK GPIO_NUM_22
|
||||
#define DISPLAY_PIN_NUM_CS GPIO_NUM_27
|
||||
#define DISPLAY_DELAY 2000
|
||||
|
||||
//--------------------------
|
||||
//----- encoder config -----
|
||||
//--------------------------
|
||||
#define ROT_ENC_A_GPIO GPIO_NUM_19
|
||||
#define ROT_ENC_B_GPIO GPIO_NUM_21
|
||||
#define ENABLE_HALF_STEPS false // Set to true to enable tracking of rotary encoder at half step resolution
|
||||
#define FLIP_DIRECTION false // Set to true to reverse the clockwise/counterclockwise sense
|
||||
|
||||
//--------------------------
|
||||
//------ calibration -------
|
||||
//--------------------------
|
||||
//use encoder test for calibration and calculate STEPS_PER_METER
|
||||
//#define ENCODER_TEST //show encoder count instead of converted meters
|
||||
#define STEPS_PER_METER 2127 //roll-v3-gummi-86.6mm - d=89.8mm
|
||||
//#define MEASURING_ROLL_DIAMETER 86.6 //roll v3 large
|
||||
//#define PI 3.14159265358979323846
|
||||
|
||||
|
||||
|
||||
//============================
|
||||
//===== global variables =====
|
||||
//============================
|
||||
//create global evaluated switch objects
|
||||
//--- inputs ---
|
||||
//create objects for switches at bottom screw temerinals
|
||||
extern gpio_evaluatedSwitch SW_START;
|
||||
extern gpio_evaluatedSwitch SW_RESET;
|
||||
extern gpio_evaluatedSwitch SW_SET;
|
||||
extern gpio_evaluatedSwitch SW_PRESET1;
|
||||
extern gpio_evaluatedSwitch SW_PRESET2;
|
||||
extern gpio_evaluatedSwitch SW_PRESET3;
|
||||
|
||||
//create global buzzer object
|
||||
extern buzzer_t buzzer;
|
||||
428
main/control.cpp
Normal file
428
main/control.cpp
Normal file
@@ -0,0 +1,428 @@
|
||||
#include "control.hpp"
|
||||
|
||||
|
||||
//========================
|
||||
//===== init encoder =====
|
||||
//========================
|
||||
QueueHandle_t init_encoder(rotary_encoder_info_t * info){
|
||||
// esp32-rotary-encoder requires that the GPIO ISR service is installed before calling rotary_encoder_register()
|
||||
ESP_ERROR_CHECK(gpio_install_isr_service(0));
|
||||
|
||||
// Initialise the rotary encoder device with the GPIOs for A and B signals
|
||||
ESP_ERROR_CHECK(rotary_encoder_init(info, ROT_ENC_A_GPIO, ROT_ENC_B_GPIO));
|
||||
ESP_ERROR_CHECK(rotary_encoder_enable_half_steps(info, ENABLE_HALF_STEPS));
|
||||
#ifdef FLIP_DIRECTION
|
||||
ESP_ERROR_CHECK(rotary_encoder_flip_direction(info));
|
||||
#endif
|
||||
|
||||
// Create a queue for events from the rotary encoder driver.
|
||||
// Tasks can read from this queue to receive up to date position information.
|
||||
QueueHandle_t event_queue = rotary_encoder_create_queue();
|
||||
ESP_ERROR_CHECK(rotary_encoder_set_queue(info, event_queue));
|
||||
return event_queue;
|
||||
}
|
||||
|
||||
|
||||
//=============================
|
||||
//========= readAdc ===========
|
||||
//=============================
|
||||
//function for multisampling an anlog input
|
||||
int readAdc(adc1_channel_t adc_channel, bool inverted = false) {
|
||||
//make multiple measurements
|
||||
int adc_reading = 0;
|
||||
for (int i = 0; i < 16; i++) {
|
||||
adc_reading += adc1_get_raw(adc_channel);
|
||||
}
|
||||
adc_reading = adc_reading / 16;
|
||||
//return original or inverted result
|
||||
if (inverted) {
|
||||
return 4095 - adc_reading;
|
||||
} else {
|
||||
return adc_reading;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
//====================
|
||||
//==== variables =====
|
||||
//====================
|
||||
static const char *TAG = "control"; //tag for logging
|
||||
|
||||
const char* systemStateStr[5] = {"COUNTING", "WINDING_START", "WINDING", "TARGET_REACHED", "MANUAL"};
|
||||
systemState_t controlState = COUNTING;
|
||||
|
||||
char buf_disp[20]; //both displays
|
||||
char buf_disp1[10];// 8 digits + decimal point + \0
|
||||
char buf_disp2[10];// 8 digits + decimal point + \0
|
||||
char buf_tmp[15];
|
||||
|
||||
rotary_encoder_info_t encoder; //encoder device/info
|
||||
QueueHandle_t encoder_queue = NULL; //encoder event queue
|
||||
rotary_encoder_state_t encoderState;
|
||||
|
||||
uint32_t timestamp_pageSwitched = 0;
|
||||
bool page = false; //store page number currently displayed
|
||||
int lengthNow = 0; //length measured in mm
|
||||
int lengthTarget = 3000; //target length in mm
|
||||
int lengthRemaining = 0; //(target - now) length needed for reaching the target
|
||||
int potiRead = 0; //voltage read from adc
|
||||
uint32_t timestamp_motorStarted = 0; //timestamp winding started
|
||||
|
||||
int lengthBeeped = 0; //only beep once per meter during encoder test
|
||||
|
||||
|
||||
//===== change State =====
|
||||
//function for changing the controlState with log output
|
||||
void changeState (systemState_t stateNew) {
|
||||
//only proceed when state actually changed
|
||||
if (controlState == stateNew){
|
||||
return; //already at target state -> nothing to do
|
||||
}
|
||||
//log change
|
||||
ESP_LOGW(TAG, "changed state from %s to %s", systemStateStr[(int)controlState], systemStateStr[(int)stateNew]);
|
||||
//change state
|
||||
controlState = stateNew;
|
||||
}
|
||||
|
||||
|
||||
//===== handle Stop Condition =====
|
||||
//function that checks whether start button is released or target is reached (used in multiple states)
|
||||
//returns true when stopped, false when no action
|
||||
bool handleStopCondition(handledDisplay * displayTop, handledDisplay * displayBot){
|
||||
//--- stop conditions ---
|
||||
//stop conditions that are checked in any mode
|
||||
//target reached
|
||||
if (lengthRemaining <= 0 ) {
|
||||
changeState(TARGET_REACHED);
|
||||
vfd_setState(false);
|
||||
displayTop->blink(1, 0, 1500, " S0LL ");
|
||||
displayBot->blink(1, 0, 1500, "ERREICHT");
|
||||
buzzer.beep(2, 100, 100);
|
||||
return true;
|
||||
}
|
||||
//start button released
|
||||
else if (SW_START.state == false) {
|
||||
changeState(COUNTING);
|
||||
vfd_setState(false);
|
||||
displayTop->blink(2, 900, 1000, "- STOP -");
|
||||
displayBot->blink(2, 900, 1000, " TASTER ");
|
||||
buzzer.beep(3, 200, 100);
|
||||
return true;
|
||||
} else {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
//===== set dynamic speed level =====
|
||||
//function that sets the vfd speed level dynamicly depending on the remaining distance
|
||||
//closer to target -> slower
|
||||
void setDynSpeedLvl(uint8_t lvlMax = 3){
|
||||
uint8_t lvl;
|
||||
//define speed level according to difference
|
||||
if (lengthRemaining < 50) {
|
||||
lvl = 0;
|
||||
} else if (lengthRemaining < 200) {
|
||||
lvl = 1;
|
||||
} else if (lengthRemaining < 600) {
|
||||
lvl = 2;
|
||||
} else { //more than last step remaining
|
||||
lvl = 3;
|
||||
}
|
||||
//limit to max lvl
|
||||
if (lvl > lvlMax){
|
||||
lvl = lvlMax;
|
||||
}
|
||||
//update vfd speed level
|
||||
vfd_setSpeedLevel(lvl);
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
//========================
|
||||
//===== control task =====
|
||||
//========================
|
||||
void task_control(void *pvParameter)
|
||||
{
|
||||
//initialize encoder
|
||||
encoder_queue = init_encoder(&encoder);
|
||||
|
||||
//initialize display
|
||||
max7219_t two7SegDisplays = display_init();
|
||||
//create two separate handled display instances
|
||||
handledDisplay displayTop(two7SegDisplays, 0);
|
||||
handledDisplay displayBot(two7SegDisplays, 8);
|
||||
|
||||
//--- display welcome msg ---
|
||||
//display welcome message on two 7 segment displays
|
||||
//currently show name and date and scrolling 'hello'
|
||||
display_ShowWelcomeMsg(two7SegDisplays);
|
||||
|
||||
|
||||
//================
|
||||
//===== loop =====
|
||||
//================
|
||||
while(1){
|
||||
vTaskDelay(20 / portTICK_PERIOD_MS);
|
||||
|
||||
//-----------------------------
|
||||
//------ handle switches ------
|
||||
//-----------------------------
|
||||
//run handle functions for all switches
|
||||
SW_START.handle();
|
||||
SW_RESET.handle();
|
||||
SW_SET.handle();
|
||||
SW_PRESET1.handle();
|
||||
SW_PRESET2.handle();
|
||||
SW_PRESET3.handle();
|
||||
|
||||
|
||||
|
||||
//----------------------------
|
||||
//------ rotary encoder ------
|
||||
//----------------------------
|
||||
// Poll current position and direction
|
||||
rotary_encoder_get_state(&encoder, &encoderState);
|
||||
//--- calculate distance ---
|
||||
//lengthNow = (float)encoderState.position * (MEASURING_ROLL_DIAMETER * PI) / 600; //TODO dont calculate constant factor every time FIXME: ROUNDING ISSUE float-int?
|
||||
lengthNow = (float)encoderState.position * 1000 / STEPS_PER_METER;
|
||||
|
||||
|
||||
|
||||
//---------------------------
|
||||
//--------- buttons ---------
|
||||
//---------------------------
|
||||
//TODO: ADD PRESET SWITCHES HERE
|
||||
//--- RESET switch ---
|
||||
if (SW_RESET.risingEdge) {
|
||||
rotary_encoder_reset(&encoder);
|
||||
lengthNow = 0;
|
||||
buzzer.beep(1, 700, 100);
|
||||
}
|
||||
|
||||
|
||||
//--- manual mode ---
|
||||
//switch to manual motor control (2 buttons + poti)
|
||||
if ( SW_PRESET2.state && (SW_PRESET1.state || SW_PRESET3.state) && controlState != MANUAL ) {
|
||||
//enable manual control
|
||||
changeState(MANUAL);
|
||||
buzzer.beep(3, 100, 60);
|
||||
}
|
||||
|
||||
|
||||
//--- set custom target length ---
|
||||
//set target length to poti position when SET switch is pressed
|
||||
if (SW_SET.state == true) {
|
||||
//read adc
|
||||
potiRead = readAdc(ADC_CHANNEL_POTI); //0-4095
|
||||
//scale to target length range
|
||||
int lengthTargetNew = (float)potiRead / 4095 * 30000;
|
||||
//apply hysteresis and round to whole meters //TODO optimize this
|
||||
if (lengthTargetNew % 1000 < 200) { //round down if less than .2 meter
|
||||
ESP_LOGD(TAG, "Poti input = %d -> rounding down", lengthTargetNew);
|
||||
lengthTargetNew = (lengthTargetNew/1000 ) * 1000; //round down
|
||||
} else if (lengthTargetNew % 1000 > 800 ) { //round up if more than .8 meter
|
||||
ESP_LOGD(TAG, "Poti input = %d -> rounding up", lengthTargetNew);
|
||||
lengthTargetNew = (lengthTargetNew/1000 + 1) * 1000; //round up
|
||||
} else {
|
||||
ESP_LOGD(TAG, "Poti input = %d -> hysteresis", lengthTargetNew);
|
||||
lengthTargetNew = lengthTarget;
|
||||
}
|
||||
//update target length and beep when effectively changed
|
||||
if (lengthTargetNew != lengthTarget) {
|
||||
//TODO update lengthTarget only at button release?
|
||||
lengthTarget = lengthTargetNew;
|
||||
ESP_LOGI(TAG, "Changed target length to %d mm", lengthTarget);
|
||||
buzzer.beep(1, 25, 10);
|
||||
}
|
||||
}
|
||||
//beep start and end of editing
|
||||
if (SW_SET.risingEdge) {
|
||||
buzzer.beep(1, 70, 50);
|
||||
}
|
||||
if (SW_SET.fallingEdge) {
|
||||
buzzer.beep(2, 70, 50);
|
||||
displayBot.blink(2, 100, 100, "S0LL ");
|
||||
}
|
||||
|
||||
|
||||
//--- target length presets ---
|
||||
if (controlState != MANUAL) { //dont apply preset length while controlling motor with preset buttons
|
||||
if (SW_PRESET1.risingEdge){
|
||||
lengthTarget = 1000;
|
||||
buzzer.beep(lengthTarget/1000, 25, 30);
|
||||
displayBot.blink(3, 100, 100, "S0LL ");
|
||||
}
|
||||
else if (SW_PRESET2.risingEdge) {
|
||||
lengthTarget = 5000;
|
||||
buzzer.beep(lengthTarget/1000, 25, 30);
|
||||
displayBot.blink(2, 100, 100, "S0LL ");
|
||||
}
|
||||
else if (SW_PRESET3.risingEdge) {
|
||||
lengthTarget = 10000;
|
||||
buzzer.beep(lengthTarget/1000, 25, 30);
|
||||
displayBot.blink(2, 100, 100, "S0LL ");
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
//---------------------------
|
||||
//--------- control ---------
|
||||
//---------------------------
|
||||
//calculate length difference
|
||||
lengthRemaining = lengthTarget - lengthNow;
|
||||
|
||||
//--- statemachine ---
|
||||
switch (controlState) {
|
||||
case COUNTING: //no motor action
|
||||
vfd_setState(false);
|
||||
//TODO check stop condition before starting - prevents motor from starting 2 cycles when
|
||||
//--- start winding to length ---
|
||||
if (SW_START.risingEdge) {
|
||||
changeState(WINDING_START);
|
||||
//TODO apply dynamic speed here too (if started when already very close)
|
||||
vfd_setSpeedLevel(1); //start at low speed
|
||||
vfd_setState(true); //start motor
|
||||
timestamp_motorStarted = esp_log_timestamp(); //save time started
|
||||
buzzer.beep(1, 100, 0);
|
||||
}
|
||||
break;
|
||||
|
||||
case WINDING_START: //wind slow for certain time
|
||||
//set vfd speed depending on remaining distance
|
||||
setDynSpeedLvl(1); //limit to speed lvl 1 (force slow start)
|
||||
if (esp_log_timestamp() - timestamp_motorStarted > 2000) {
|
||||
changeState(WINDING);
|
||||
}
|
||||
handleStopCondition(&displayTop, &displayBot); //stops if button released or target reached
|
||||
//TODO: cancel when there was no cable movement during start time?
|
||||
break;
|
||||
|
||||
case WINDING: //wind fast, slow down when close
|
||||
//set vfd speed depending on remaining distance
|
||||
setDynSpeedLvl(); //slow down when close to target
|
||||
handleStopCondition(&displayTop, &displayBot); //stops if button released or target reached
|
||||
//TODO: cancel when there is no cable movement anymore e.g. empty / timeout?
|
||||
break;
|
||||
|
||||
case TARGET_REACHED:
|
||||
vfd_setState(false);
|
||||
//switch to counting state when no longer at or above target length
|
||||
if ( lengthRemaining > 0 ) {
|
||||
changeState(COUNTING);
|
||||
}
|
||||
//show msg when trying to start, but target is reached
|
||||
if (SW_START.risingEdge){
|
||||
buzzer.beep(3, 40, 30);
|
||||
displayTop.blink(2, 600, 800, " S0LL ");
|
||||
displayBot.blink(2, 600, 800, "ERREICHT");
|
||||
}
|
||||
break;
|
||||
|
||||
case MANUAL: //manually control motor via preset buttons + poti
|
||||
//read poti value
|
||||
potiRead = readAdc(ADC_CHANNEL_POTI); //0-4095
|
||||
//scale poti to speed levels 0-3
|
||||
uint8_t level = round( (float)potiRead / 4095 * 3 );
|
||||
//exit manual mode if preset2 released
|
||||
if ( SW_PRESET2.state == false ) {
|
||||
changeState(COUNTING);
|
||||
buzzer.beep(1, 1000, 100);
|
||||
}
|
||||
//P2 + P1 -> turn left
|
||||
else if ( SW_PRESET1.state && !SW_PRESET3.state ) {
|
||||
vfd_setSpeedLevel(level); //TODO: use poti input for level
|
||||
vfd_setState(true, REV);
|
||||
sprintf(buf_disp2, "[--%02i ", level);
|
||||
// 123 45 678
|
||||
}
|
||||
//P2 + P3 -> turn right
|
||||
else if ( SW_PRESET3.state && !SW_PRESET1.state ) {
|
||||
vfd_setSpeedLevel(level); //TODO: use poti input for level
|
||||
vfd_setState(true, FWD);
|
||||
sprintf(buf_disp2, " %02i--]", level);
|
||||
}
|
||||
//no valid switch combination -> turn off motor
|
||||
else {
|
||||
vfd_setState(false);
|
||||
sprintf(buf_disp2, " %02i ", level);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
//--------------------------
|
||||
//------ encoder test ------
|
||||
//--------------------------
|
||||
#ifdef ENCODER_TEST
|
||||
//run display handle functions
|
||||
displayTop.handle();
|
||||
displayBot.handle();
|
||||
//-- show encoder steps on display1 ---
|
||||
sprintf(buf_disp1, "EN %05d", encoderState.position); //count
|
||||
displayTop.showString(buf_disp1);
|
||||
//--- show converted distance on display2 ---
|
||||
sprintf(buf_disp2, "Met %5.3f", (float)lengthNow/1000); //m
|
||||
displayBot.showString(buf_disp2);
|
||||
//--- beep every 1m ---
|
||||
//note: only works precicely in forward/positive direction
|
||||
if (lengthNow % 1000 < 50) { //with tolerance in case of missed exact value
|
||||
if (fabs(lengthNow - lengthBeeped) >= 900) { //dont beep multiple times at same meter
|
||||
//TODO: add case for reverse direction. currently beeps 0.1 too early
|
||||
buzzer.beep(1, 400, 100 );
|
||||
lengthBeeped = lengthNow;
|
||||
}
|
||||
}
|
||||
#else
|
||||
|
||||
//--------------------------
|
||||
//-------- display1 --------
|
||||
//--------------------------
|
||||
//run handle function
|
||||
displayTop.handle();
|
||||
//show current position on display
|
||||
sprintf(buf_tmp, "1ST %5.4f", (float)lengthNow/1000);
|
||||
// 123456789
|
||||
//limit length to 8 digits + decimal point (drop decimal places when it does not fit)
|
||||
sprintf(buf_disp1, "%.9s", buf_tmp);
|
||||
displayTop.showString(buf_disp1);
|
||||
|
||||
|
||||
//--------------------------
|
||||
//-------- display2 --------
|
||||
//--------------------------
|
||||
//run handle function
|
||||
displayBot.handle();
|
||||
//setting target length: blink target length
|
||||
if (SW_SET.state == true){
|
||||
sprintf(buf_tmp, "S0LL%5.3f", (float)lengthTarget/1000);
|
||||
displayBot.blinkStrings(buf_tmp, "S0LL ", 300, 100);
|
||||
}
|
||||
//manual state: blink "manual"
|
||||
else if (controlState == MANUAL) {
|
||||
displayBot.blinkStrings(" MANUAL ", buf_disp2, 1000, 1000);
|
||||
}
|
||||
//otherwise show target length
|
||||
else {
|
||||
//sprintf(buf_disp2, "%06.1f cm", (float)lengthTarget/10); //cm
|
||||
sprintf(buf_tmp, "S0LL%5.3f", (float)lengthTarget/1000); //m
|
||||
// 1234 5678
|
||||
displayBot.showString(buf_tmp);
|
||||
}
|
||||
|
||||
|
||||
#endif
|
||||
|
||||
//TODO: blink disp2 when set button pressed
|
||||
//TODO: blink disp2 when preset button pressed (exept manual mode)
|
||||
//TODO: write "MAN CTL" to disp2 when in manual mode
|
||||
//TODO: display or blink "REACHED" when reached state and start pressed
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
31
main/control.hpp
Normal file
31
main/control.hpp
Normal file
@@ -0,0 +1,31 @@
|
||||
#pragma once
|
||||
extern "C"
|
||||
{
|
||||
#include <stdio.h>
|
||||
#include <freertos/FreeRTOS.h>
|
||||
#include <freertos/task.h>
|
||||
#include <esp_idf_version.h>
|
||||
#include "freertos/queue.h"
|
||||
#include "esp_system.h"
|
||||
#include "esp_log.h"
|
||||
#include "driver/adc.h"
|
||||
|
||||
#include "rotary_encoder.h"
|
||||
#include "max7219.h"
|
||||
|
||||
}
|
||||
#include <cmath>
|
||||
|
||||
#include "config.hpp"
|
||||
#include "gpio_evaluateSwitch.hpp"
|
||||
#include "buzzer.hpp"
|
||||
#include "vfd.hpp"
|
||||
#include "display.hpp"
|
||||
|
||||
|
||||
|
||||
typedef enum systemState_t {COUNTING, WINDING_START, WINDING, TARGET_REACHED, MANUAL} systemState_t;
|
||||
extern const char* systemStateStr[5];
|
||||
|
||||
|
||||
void task_control(void *pvParameter);
|
||||
198
main/display.cpp
Normal file
198
main/display.cpp
Normal file
@@ -0,0 +1,198 @@
|
||||
#include "display.hpp"
|
||||
|
||||
|
||||
//=== variables ===
|
||||
static const char *TAG = "display"; //tag for logging
|
||||
|
||||
|
||||
|
||||
//==============================
|
||||
//======== init display ========
|
||||
//==============================
|
||||
//initialize display with parameters defined in config.hpp
|
||||
//TODO: dont use global variables/macros here
|
||||
max7219_t display_init(){
|
||||
|
||||
ESP_LOGI(TAG, "initializing display...");
|
||||
// Configure SPI bus
|
||||
spi_bus_config_t cfg;
|
||||
memset(&cfg, 0, sizeof(spi_bus_config_t)); //init bus config with 0 to prevent bugs with random flags
|
||||
cfg.mosi_io_num = DISPLAY_PIN_NUM_MOSI;
|
||||
cfg.miso_io_num = -1;
|
||||
cfg.sclk_io_num = DISPLAY_PIN_NUM_CLK;
|
||||
cfg.quadwp_io_num = -1;
|
||||
cfg.quadhd_io_num = -1;
|
||||
cfg.max_transfer_sz = 0;
|
||||
cfg.flags = 0;
|
||||
ESP_ERROR_CHECK(spi_bus_initialize(HOST, &cfg, 1));
|
||||
|
||||
// Configure device
|
||||
max7219_t dev;
|
||||
dev.cascade_size = 2;
|
||||
dev.digits = 0;
|
||||
dev.mirrored = true;
|
||||
ESP_ERROR_CHECK(max7219_init_desc(&dev, HOST, MAX7219_MAX_CLOCK_SPEED_HZ, DISPLAY_PIN_NUM_CS));
|
||||
ESP_ERROR_CHECK(max7219_init(&dev));
|
||||
//0...15
|
||||
ESP_ERROR_CHECK(max7219_set_brightness(&dev, 8));
|
||||
return dev;
|
||||
//display = dev;
|
||||
ESP_LOGI(TAG, "initializing display - done");
|
||||
}
|
||||
|
||||
|
||||
|
||||
//===================================
|
||||
//======= display welcome msg =======
|
||||
//===================================
|
||||
void display_ShowWelcomeMsg(max7219_t dev){
|
||||
//display welcome message on two 7 segment displays
|
||||
//show name and date
|
||||
ESP_LOGI(TAG, "showing startup message...");
|
||||
max7219_clear(&dev);
|
||||
max7219_draw_text_7seg(&dev, 0, "CUTTER 20.08.2022");
|
||||
// 1234567812 34 5678
|
||||
vTaskDelay(pdMS_TO_TICKS(700));
|
||||
//scroll "hello" over 2 displays
|
||||
for (int offset = 0; offset < 23; offset++) {
|
||||
max7219_clear(&dev);
|
||||
char hello[40] = " HELL0 ";
|
||||
max7219_draw_text_7seg(&dev, 0, hello + (22 - offset) );
|
||||
vTaskDelay(pdMS_TO_TICKS(50));
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
//---------------------------------
|
||||
//---------- constructor ----------
|
||||
//---------------------------------
|
||||
handledDisplay::handledDisplay(max7219_t displayDevice, uint8_t posStart_f) {
|
||||
ESP_LOGI(TAG, "Creating handledDisplay instance with startPos at %i", posStart);
|
||||
//copy variables
|
||||
dev = displayDevice;
|
||||
posStart = posStart_f;
|
||||
}
|
||||
|
||||
|
||||
|
||||
//--------------------------------
|
||||
//---------- showString ----------
|
||||
//--------------------------------
|
||||
//function that displays a given string on the display
|
||||
void handledDisplay::showString(const char * buf, uint8_t pos_f){
|
||||
//calculate actual absolute position
|
||||
posCurrent = posStart + pos_f;
|
||||
//copy the desired string
|
||||
strcpy(strOn, buf);
|
||||
//exit blinking mode
|
||||
if (mode == displayMode::BLINK_STRINGS){
|
||||
mode = displayMode::NORMAL;
|
||||
ESP_LOGI(TAG, "pos:%i - disable blink strings mode -> normal mode str='%s'", posStart, strOn);
|
||||
}
|
||||
handle(); //draws the text depending on mode
|
||||
}
|
||||
|
||||
|
||||
|
||||
//TODO: blinkStrings() and blink() are very similar - can be optimized?
|
||||
//only difficulty currently is the reset behaivor of blinkStrings through showString (blink does not reset)
|
||||
|
||||
//----------------------------------
|
||||
//---------- blinkStrings ----------
|
||||
//----------------------------------
|
||||
//function switches between two strings in a given interval
|
||||
void handledDisplay::blinkStrings(const char * strOn_f, const char * strOff_f, uint32_t msOn_f, uint32_t msOff_f){
|
||||
//copy/update variables
|
||||
strcpy(strOn, strOn_f);
|
||||
strcpy(strOff, strOff_f);
|
||||
msOn = msOn_f;
|
||||
msOff = msOff_f;
|
||||
//if changed to blink mode just now:
|
||||
if (mode != displayMode::BLINK_STRINGS) {
|
||||
//switch mode
|
||||
ESP_LOGI(TAG, "pos:%i - toggle blink strings mode on/off=%d/%d stings='%s'/'%s'", posStart, msOn, msOff, strOn, strOff);
|
||||
mode = displayMode::BLINK_STRINGS;
|
||||
//start with on state
|
||||
state = true;
|
||||
timestampOn = esp_log_timestamp();
|
||||
}
|
||||
//run handle function for display update
|
||||
handle();
|
||||
}
|
||||
|
||||
|
||||
|
||||
//-------------------------------
|
||||
//------------ blink ------------
|
||||
//-------------------------------
|
||||
//function triggers certain count and interval of off durations
|
||||
void handledDisplay::blink(uint8_t count_f, uint32_t msOn_f, uint32_t msOff_f, const char * strOff_f) {
|
||||
//copy/update parameters
|
||||
count = count_f;
|
||||
msOn = msOn_f;
|
||||
msOff = msOff_f;
|
||||
strcpy(strOff, strOff_f);
|
||||
//FIXME this strings length must be dynamic depending on display size (posEnd - posStart) -> otherwise overwrites next segments if other display size or start pos
|
||||
//if changed to blink mode just now:
|
||||
if (mode != displayMode::BLINK) {
|
||||
//set to blink mode
|
||||
mode = displayMode::BLINK;
|
||||
ESP_LOGI(TAG, "pos:%i - start blinking: count=%i on/off=%d/%d sting='%s'",posStart, count, msOn, msOff, strOff);
|
||||
//start with off state
|
||||
state = false;
|
||||
timestampOff = esp_log_timestamp();
|
||||
}
|
||||
//run handle function for display update
|
||||
handle();
|
||||
}
|
||||
|
||||
|
||||
|
||||
//--------------------------------
|
||||
//------------ handle ------------
|
||||
//--------------------------------
|
||||
//function that handles time based modes
|
||||
//writes text to the 7 segment display depending on the current mode
|
||||
void handledDisplay::handle() {
|
||||
switch (mode){
|
||||
case displayMode::NORMAL:
|
||||
//daw given string
|
||||
max7219_draw_text_7seg(&dev, posCurrent, strOn);
|
||||
break;
|
||||
|
||||
case displayMode::BLINK:
|
||||
case displayMode::BLINK_STRINGS:
|
||||
//--- define state on/off ---
|
||||
if (state == true){ //display in ON state
|
||||
if (esp_log_timestamp() - timestampOn > msOn){
|
||||
state = false;
|
||||
timestampOff = esp_log_timestamp();
|
||||
//decrement remaining counts in BLINK mode each cycle
|
||||
if (mode == displayMode::BLINK) count--;
|
||||
}
|
||||
} else { //display in OFF state
|
||||
if (esp_log_timestamp() - timestampOff > msOff) {
|
||||
state = true;
|
||||
timestampOn = esp_log_timestamp();
|
||||
}
|
||||
}
|
||||
//--- draw text of current state ---
|
||||
if (state) {
|
||||
max7219_draw_text_7seg(&dev, posStart, strOn);
|
||||
} else {
|
||||
max7219_draw_text_7seg(&dev, posStart, strOff);
|
||||
}
|
||||
|
||||
//--- check finished condition in BLINK mode ---
|
||||
if (mode == displayMode::BLINK){
|
||||
if (count == 0) {
|
||||
mode = displayMode::NORMAL;
|
||||
ESP_LOGI(TAG, "pos:%i - finished blinking -> normal mode", posStart);
|
||||
}
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
65
main/display.hpp
Normal file
65
main/display.hpp
Normal file
@@ -0,0 +1,65 @@
|
||||
#pragma once
|
||||
extern "C"
|
||||
{
|
||||
#include <stdio.h>
|
||||
#include <freertos/FreeRTOS.h>
|
||||
#include <freertos/task.h>
|
||||
#include <esp_idf_version.h>
|
||||
#include "freertos/queue.h"
|
||||
#include "esp_system.h"
|
||||
#include "esp_log.h"
|
||||
#include "driver/adc.h"
|
||||
|
||||
#include <max7219.h>
|
||||
#include "rotary_encoder.h"
|
||||
}
|
||||
#include <cstring>
|
||||
|
||||
|
||||
#include "config.hpp"
|
||||
|
||||
//function for initializing the display using configuration from macros in config.hpp
|
||||
max7219_t display_init();
|
||||
|
||||
//show welcome message on the entire display
|
||||
void display_ShowWelcomeMsg(max7219_t displayDevice);
|
||||
|
||||
enum class displayMode {NORMAL, BLINK_STRINGS, BLINK};
|
||||
|
||||
class handledDisplay {
|
||||
public:
|
||||
//--- constructor ---
|
||||
//TODO add posMax to prevent writing in segments of other instance
|
||||
handledDisplay(max7219_t displayDevice, uint8_t posStart);
|
||||
|
||||
//--- methods ---
|
||||
void showString(const char * buf, uint8_t pos = 0);
|
||||
//function switches between two strings in a given interval
|
||||
void blinkStrings(const char * strOn, const char * strOff, uint32_t msOn, uint32_t msOff);
|
||||
//triggers certain count of blinking between currently shown string and off or optional certain string
|
||||
void blink(uint8_t count, uint32_t msOn, uint32_t msOff, const char * strOff = " ");
|
||||
//function that handles time based modes and writes text to display
|
||||
void handle(); //has to be run regularly when blink method is used
|
||||
|
||||
//TODO: blinkStrings and blink are very similar - optimize?
|
||||
//TODO: add 'scroll string' method
|
||||
|
||||
private:
|
||||
|
||||
//--- variables ---
|
||||
//config
|
||||
max7219_t dev;
|
||||
uint8_t posStart; //absolute position this display instance starts (e.g. multiple or very long 7 segment display)
|
||||
uint8_t posCurrent;
|
||||
|
||||
displayMode mode = displayMode::NORMAL;
|
||||
//blink modes
|
||||
uint8_t count = 0;
|
||||
char strOn[20];
|
||||
char strOff[20];
|
||||
bool state = false;
|
||||
uint32_t msOn;
|
||||
uint32_t msOff;
|
||||
uint32_t timestampOn;
|
||||
uint32_t timestampOff;
|
||||
};
|
||||
191
main/main.c
191
main/main.c
@@ -1,191 +0,0 @@
|
||||
#include <stdio.h>
|
||||
#include <freertos/FreeRTOS.h>
|
||||
#include <freertos/task.h>
|
||||
#include <esp_idf_version.h>
|
||||
#include "freertos/queue.h"
|
||||
#include "esp_system.h"
|
||||
#include "esp_log.h"
|
||||
|
||||
#include <max7219.h>
|
||||
#include "rotary_encoder.h"
|
||||
|
||||
//--------------------------
|
||||
//----- display config -----
|
||||
//--------------------------
|
||||
#if ESP_IDF_VERSION < ESP_IDF_VERSION_VAL(4, 0, 0)
|
||||
#define HOST HSPI_HOST
|
||||
#else
|
||||
#define HOST SPI2_HOST
|
||||
#endif
|
||||
#define DISPLAY_PIN_NUM_MOSI 23
|
||||
#define DISPLAY_PIN_NUM_CLK 18
|
||||
#define DISPLAY_PIN_NUM_CS 21
|
||||
#define DISPLAY_DELAY 2000
|
||||
|
||||
//--------------------------
|
||||
//----- encoder config -----
|
||||
//--------------------------
|
||||
#define TAG "app"
|
||||
#define ROT_ENC_A_GPIO 16
|
||||
#define ROT_ENC_B_GPIO 17
|
||||
#define ENABLE_HALF_STEPS false // Set to true to enable tracking of rotary encoder at half step resolution
|
||||
#define FLIP_DIRECTION false // Set to true to reverse the clockwise/counterclockwise sense
|
||||
|
||||
#define MEASURING_ROLL_DIAMETER 44
|
||||
#define PI 3.14159265358979323846
|
||||
|
||||
|
||||
|
||||
|
||||
void task(void *pvParameter)
|
||||
{
|
||||
|
||||
//========================
|
||||
//===== init encoder =====
|
||||
//========================
|
||||
// esp32-rotary-encoder requires that the GPIO ISR service is installed before calling rotary_encoder_register()
|
||||
ESP_ERROR_CHECK(gpio_install_isr_service(0));
|
||||
|
||||
// Initialise the rotary encoder device with the GPIOs for A and B signals
|
||||
rotary_encoder_info_t info = { 0 };
|
||||
ESP_ERROR_CHECK(rotary_encoder_init(&info, ROT_ENC_A_GPIO, ROT_ENC_B_GPIO));
|
||||
ESP_ERROR_CHECK(rotary_encoder_enable_half_steps(&info, ENABLE_HALF_STEPS));
|
||||
#ifdef FLIP_DIRECTION
|
||||
ESP_ERROR_CHECK(rotary_encoder_flip_direction(&info));
|
||||
#endif
|
||||
|
||||
// Create a queue for events from the rotary encoder driver.
|
||||
// Tasks can read from this queue to receive up to date position information.
|
||||
QueueHandle_t event_queue = rotary_encoder_create_queue();
|
||||
ESP_ERROR_CHECK(rotary_encoder_set_queue(&info, event_queue));
|
||||
|
||||
|
||||
|
||||
|
||||
//========================
|
||||
//===== init display =====
|
||||
//========================
|
||||
// Configure SPI bus
|
||||
spi_bus_config_t cfg = {
|
||||
.mosi_io_num = DISPLAY_PIN_NUM_MOSI,
|
||||
.miso_io_num = -1,
|
||||
.sclk_io_num = DISPLAY_PIN_NUM_CLK,
|
||||
.quadwp_io_num = -1,
|
||||
.quadhd_io_num = -1,
|
||||
.max_transfer_sz = 0,
|
||||
.flags = 0
|
||||
};
|
||||
ESP_ERROR_CHECK(spi_bus_initialize(HOST, &cfg, 1));
|
||||
|
||||
// Configure device
|
||||
max7219_t dev = {
|
||||
.cascade_size = 1,
|
||||
.digits = 8,
|
||||
.mirrored = true
|
||||
};
|
||||
ESP_ERROR_CHECK(max7219_init_desc(&dev, HOST, MAX7219_MAX_CLOCK_SPEED_HZ, DISPLAY_PIN_NUM_CS));
|
||||
|
||||
ESP_ERROR_CHECK(max7219_init(&dev));
|
||||
|
||||
//0...15
|
||||
ESP_ERROR_CHECK(max7219_set_brightness(&dev, 12));
|
||||
|
||||
|
||||
|
||||
char buf[10]; // 8 digits + decimal point + \0
|
||||
int32_t distance_mm = 0;
|
||||
|
||||
//display startup message
|
||||
max7219_clear(&dev);
|
||||
max7219_draw_text_7seg(&dev, 0, "ABCDEFGH");
|
||||
printf("showing startup message...");
|
||||
vTaskDelay(pdMS_TO_TICKS(1000));
|
||||
|
||||
|
||||
//===== loop =====
|
||||
while (1)
|
||||
{
|
||||
|
||||
|
||||
vTaskDelay(pdMS_TO_TICKS(10)); //limit processing of events
|
||||
|
||||
|
||||
// Wait for incoming events on the event queue.
|
||||
rotary_encoder_event_t event = { 0 };
|
||||
if (xQueueReceive(event_queue, &event, 1000 / portTICK_PERIOD_MS) == pdTRUE)
|
||||
{
|
||||
ESP_LOGI(TAG, "Event: position %d, direction %s", event.state.position,
|
||||
event.state.direction ? (event.state.direction == ROTARY_ENCODER_DIRECTION_CLOCKWISE ? "CW" : "CCW") : "NOT_SET");
|
||||
|
||||
|
||||
//--- calculate distalce ---
|
||||
distance_mm = event.state.position * (MEASURING_ROLL_DIAMETER * PI / 600); //TODO dont calculate constant factor every time
|
||||
//--- show current position on display ---
|
||||
//sprintf(buf, "%08d", event.state.position);
|
||||
//--- show current distance in cm on display ---
|
||||
sprintf(buf, "%06.1f cm", (float)distance_mm/10);
|
||||
//printf("float num\n");
|
||||
max7219_clear(&dev);
|
||||
max7219_draw_text_7seg(&dev, 0, buf);
|
||||
}
|
||||
else //no event for 1s
|
||||
{
|
||||
// Poll current position and direction
|
||||
rotary_encoder_state_t state = { 0 };
|
||||
ESP_ERROR_CHECK(rotary_encoder_get_state(&info, &state));
|
||||
ESP_LOGI(TAG, "Poll: position %d, direction %s", state.position,
|
||||
state.direction ? (state.direction == ROTARY_ENCODER_DIRECTION_CLOCKWISE ? "CW" : "CCW") : "NOT_SET");
|
||||
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
//display test
|
||||
//float count = 0;
|
||||
|
||||
// printf("Display cycle\n");
|
||||
//
|
||||
// max7219_clear(&dev);
|
||||
// max7219_draw_text_7seg(&dev, 0, "12345678");
|
||||
// printf("num");
|
||||
// vTaskDelay(pdMS_TO_TICKS(DISPLAY_DELAY));
|
||||
//
|
||||
// max7219_clear(&dev);
|
||||
// max7219_draw_text_7seg(&dev, 0, "ABCDEFGH");
|
||||
// printf("text");
|
||||
// vTaskDelay(pdMS_TO_TICKS(DISPLAY_DELAY));
|
||||
//
|
||||
//
|
||||
// if (count > 20){
|
||||
// count = 0;
|
||||
// } else {
|
||||
// count += 0.005;
|
||||
// }
|
||||
//
|
||||
// sprintf(buf, "%06.3f m", count);
|
||||
// //printf("float num\n");
|
||||
// max7219_clear(&dev);
|
||||
// max7219_draw_text_7seg(&dev, 0, buf);
|
||||
// vTaskDelay(pdMS_TO_TICKS(10));
|
||||
//
|
||||
// max7219_clear(&dev);
|
||||
// sprintf(buf, "%08x", 12345678);
|
||||
// printf("num\n");
|
||||
// max7219_draw_text_7seg(&dev, 0, buf);
|
||||
// vTaskDelay(pdMS_TO_TICKS(DISPLAY_DELAY));
|
||||
|
||||
|
||||
// }
|
||||
//}
|
||||
|
||||
void app_main()
|
||||
{
|
||||
xTaskCreate(task, "task", configMINIMAL_STACK_SIZE * 3, NULL, 5, NULL);
|
||||
}
|
||||
|
||||
|
||||
90
main/main.cpp
Normal file
90
main/main.cpp
Normal file
@@ -0,0 +1,90 @@
|
||||
extern "C"
|
||||
{
|
||||
#include <stdio.h>
|
||||
#include <freertos/FreeRTOS.h>
|
||||
#include <freertos/task.h>
|
||||
#include <esp_idf_version.h>
|
||||
#include "freertos/queue.h"
|
||||
#include "esp_system.h"
|
||||
#include "esp_log.h"
|
||||
#include "driver/adc.h"
|
||||
}
|
||||
|
||||
#include "config.hpp"
|
||||
#include "control.hpp"
|
||||
#include "buzzer.hpp"
|
||||
|
||||
|
||||
//=================================
|
||||
//=========== functions ===========
|
||||
//=================================
|
||||
//function to configure gpio pin as output
|
||||
void gpio_configure_output(gpio_num_t gpio_pin){
|
||||
gpio_pad_select_gpio(gpio_pin);
|
||||
gpio_set_direction(gpio_pin, GPIO_MODE_OUTPUT);
|
||||
}
|
||||
|
||||
void init_gpios(){
|
||||
//initialize all outputs
|
||||
//4x stepper mosfets
|
||||
gpio_configure_output(GPIO_VFD_FWD);
|
||||
gpio_configure_output(GPIO_VFD_D0);
|
||||
gpio_configure_output(GPIO_VFD_D1);
|
||||
//gpio_configure_output(GPIO_VFD_D2); only used with 7.5kw vfd
|
||||
//2x power mosfets
|
||||
gpio_configure_output(GPIO_VFD_REV);
|
||||
gpio_configure_output(GPIO_MOS2);
|
||||
//onboard relay and buzzer
|
||||
gpio_configure_output(GPIO_RELAY);
|
||||
gpio_configure_output(GPIO_BUZZER);
|
||||
//5v regulator
|
||||
gpio_configure_output(GPIO_NUM_17);
|
||||
|
||||
//initialize and configure ADC
|
||||
adc1_config_width(ADC_WIDTH_BIT_12); //=> max resolution 4096
|
||||
adc1_config_channel_atten(ADC_CHANNEL_POTI, ADC_ATTEN_DB_11); //max voltage
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
||||
//======================================
|
||||
//============ 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();
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
//======================================
|
||||
//=========== main function ============
|
||||
//======================================
|
||||
extern "C" void app_main()
|
||||
{
|
||||
//init outputs
|
||||
init_gpios();
|
||||
|
||||
//enable 5V volate regulator
|
||||
gpio_set_level(GPIO_NUM_17, 1);
|
||||
|
||||
//define loglevel
|
||||
esp_log_level_set("*", ESP_LOG_INFO);
|
||||
esp_log_level_set("buzzer", ESP_LOG_ERROR);
|
||||
esp_log_level_set("control", ESP_LOG_INFO);
|
||||
|
||||
//create task for controlling the machine
|
||||
xTaskCreate(task_control, "task_control", configMINIMAL_STACK_SIZE * 3, NULL, 5, NULL);
|
||||
//create task for handling the buzzer
|
||||
xTaskCreate(&task_buzzer, "task_buzzer", 2048, NULL, 2, NULL);
|
||||
|
||||
//beep at startup
|
||||
buzzer.beep(3, 70, 50);
|
||||
}
|
||||
116
main/vfd.cpp
Normal file
116
main/vfd.cpp
Normal file
@@ -0,0 +1,116 @@
|
||||
#include "vfd.hpp"
|
||||
|
||||
#define CHECK_BIT(var,pos) (((var)>>(pos)) & 1)
|
||||
|
||||
const char* vfd_directionStr[2] = {"FWD", "REV"};
|
||||
static const char *TAG = "vfd";
|
||||
uint8_t level = 0; //current speed level
|
||||
bool state = false; //current state
|
||||
vfd_direction_t direction = FWD; //current direction
|
||||
|
||||
|
||||
//=============================
|
||||
//========= setState ==========
|
||||
//=============================
|
||||
void vfd_setState(bool stateNew, vfd_direction_t directionNew){
|
||||
//only proceed and send log output when state or direction actually changed
|
||||
if ( state == stateNew && direction == directionNew ) {
|
||||
//already at target state and target direction -> do nothing
|
||||
return;
|
||||
}
|
||||
|
||||
//log old and new state
|
||||
ESP_LOGI(TAG, "CHANGING vfd state from: %i %s", (int)state, vfd_directionStr[(int)direction]);
|
||||
ESP_LOGI(TAG, "CHANGING vfd state to: %i %s", (int)stateNew, vfd_directionStr[(int)directionNew]);
|
||||
//update stored state
|
||||
state = stateNew;
|
||||
direction = directionNew;
|
||||
|
||||
//turn motor on/off with target direction
|
||||
if (state == true) {
|
||||
switch (direction) {
|
||||
case FWD:
|
||||
gpio_set_level(GPIO_VFD_REV, 0);
|
||||
gpio_set_level(GPIO_VFD_FWD, 1);
|
||||
break;
|
||||
case REV:
|
||||
gpio_set_level(GPIO_VFD_FWD, 0);
|
||||
gpio_set_level(GPIO_VFD_REV, 1);
|
||||
break;
|
||||
}
|
||||
gpio_set_level(GPIO_RELAY, 1);
|
||||
} else {
|
||||
gpio_set_level(GPIO_VFD_FWD, 0);
|
||||
gpio_set_level(GPIO_VFD_REV, 0);
|
||||
gpio_set_level(GPIO_RELAY, 0);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
//=============================
|
||||
//======= setSpeedLevel =======
|
||||
//=============================
|
||||
void vfd_setSpeedLevel(uint8_t levelNew){
|
||||
//set speed level of VFD
|
||||
|
||||
//only proceed and send log output when level is actually changed
|
||||
if (level == levelNew) {
|
||||
//already at target level -> nothing todo
|
||||
return;
|
||||
}
|
||||
|
||||
//log change
|
||||
ESP_LOGI(TAG, "CHANGING speed level from %i to %i", level, levelNew);
|
||||
//update stored level
|
||||
level = levelNew;
|
||||
|
||||
//bit:2 1 0
|
||||
//lvl D2 D1 D0 Hz
|
||||
//0 0 0 0 default
|
||||
//1 0 0 1 1
|
||||
//2 0 1 0 3
|
||||
//3 0 1 1 9
|
||||
//4 1 0 0 16
|
||||
//5 1 0 1 25
|
||||
//6 1 1 0 50
|
||||
//7 1 1 1 70
|
||||
|
||||
//limit to 7
|
||||
if (level > 3) {
|
||||
level = 3;
|
||||
}
|
||||
|
||||
//variables for logging the pin state
|
||||
//bool D0, D1, D2;
|
||||
bool D0, D1;
|
||||
|
||||
//set output state according to corresponding bit state
|
||||
if CHECK_BIT(level, 0) {
|
||||
D0 = true;
|
||||
gpio_set_level(GPIO_VFD_D0, 1);
|
||||
} else {
|
||||
D0 = false;
|
||||
gpio_set_level(GPIO_VFD_D0, 0);
|
||||
}
|
||||
|
||||
if CHECK_BIT(level, 1) {
|
||||
D1 = true;
|
||||
gpio_set_level(GPIO_VFD_D1, 1);
|
||||
} else {
|
||||
D1 = false;
|
||||
gpio_set_level(GPIO_VFD_D1, 0);
|
||||
}
|
||||
|
||||
// if CHECK_BIT(level, 2) {
|
||||
// D2 = true;
|
||||
// gpio_set_level(GPIO_VFD_D2, 1);
|
||||
// } else {
|
||||
// D2 = false;
|
||||
// gpio_set_level(GPIO_VFD_D2, 0);
|
||||
// }
|
||||
|
||||
//log pin state
|
||||
//ESP_LOGI(TAG, " - pin state: D2=%i, D1=%i, D0=%i", (int)D2, (int)D1, (int)D0);
|
||||
ESP_LOGI(TAG, " - pin state: D1=%i, D0=%i", (int)D1, (int)D0);
|
||||
}
|
||||
23
main/vfd.hpp
Normal file
23
main/vfd.hpp
Normal file
@@ -0,0 +1,23 @@
|
||||
#pragma once
|
||||
extern "C"
|
||||
{
|
||||
#include <stdio.h>
|
||||
#include <freertos/FreeRTOS.h>
|
||||
#include <freertos/task.h>
|
||||
#include "freertos/queue.h"
|
||||
#include "esp_system.h"
|
||||
#include "esp_log.h"
|
||||
}
|
||||
|
||||
#include "config.hpp"
|
||||
|
||||
//enum defining motor direction
|
||||
typedef enum vfd_direction_t {FWD, REV} vfd_direction_t;
|
||||
//strubg array to be able to log direction state as string
|
||||
extern const char* vfd_directionStr[2];
|
||||
|
||||
//function for setting the state and optional direction of the motor: on/off, FWD/REV (default FWD)
|
||||
void vfd_setState(bool stateNew, vfd_direction_t direction = FWD);
|
||||
|
||||
//function for setting the speed level (0-3)
|
||||
void vfd_setSpeedLevel(uint8_t levelNew = 0);
|
||||
@@ -721,10 +721,10 @@ CONFIG_LOG_DEFAULT_LEVEL_INFO=y
|
||||
# CONFIG_LOG_DEFAULT_LEVEL_DEBUG is not set
|
||||
# CONFIG_LOG_DEFAULT_LEVEL_VERBOSE is not set
|
||||
CONFIG_LOG_DEFAULT_LEVEL=3
|
||||
CONFIG_LOG_MAXIMUM_EQUALS_DEFAULT=y
|
||||
# CONFIG_LOG_MAXIMUM_EQUALS_DEFAULT is not set
|
||||
# CONFIG_LOG_MAXIMUM_LEVEL_DEBUG is not set
|
||||
# CONFIG_LOG_MAXIMUM_LEVEL_VERBOSE is not set
|
||||
CONFIG_LOG_MAXIMUM_LEVEL=3
|
||||
CONFIG_LOG_MAXIMUM_LEVEL_VERBOSE=y
|
||||
CONFIG_LOG_MAXIMUM_LEVEL=5
|
||||
CONFIG_LOG_COLORS=y
|
||||
CONFIG_LOG_TIMESTAMP_SOURCE_RTOS=y
|
||||
# CONFIG_LOG_TIMESTAMP_SOURCE_SYSTEM is not set
|
||||
|
||||
Reference in New Issue
Block a user