42 Commits

Author SHA1 Message Date
jonny_l480
3a99b8bc5c Adjust analog-sw thresholds, Disable logging (loglevel)
=> tested system with new stripboard and actual hardware: system
works as expected with new all combinations of the 4 switches
connected to 1 adc

- Adjust lookup voltage for switch combinations, after connecting the
stripboard to actualy used pcb (apparently there was a >100
difference using an other adc channel + pcb)

- define loglevel for analogswitches to WARN
2022-09-12 13:19:54 +02:00
jonny_ji7
451981b165 Rework switch-assignment, Update connection-plan
Rework config.cpp and config.hpp:
 - different naming convention for evaluated switch objects
 - thus updated macros for switches

 - add new evalswitch instances for 4 switches on 1 adc
 - update switch assignment, use the 4 new inputs

Update connection plan with new assignment, add stripboard details
2022-09-12 11:50:45 +02:00
jonny_ji7
1f53fabd19 Create gpio_adc component - outsource readAdc()
remove duplicate code:
function readAdc was used in multiple files, outsourced this to gpio
component
2022-09-12 11:19:47 +02:00
jonny_ji7
d2d85952df Add evalSwitch instance for sw on adc (testing)
Test all new changes in switchesAnalog and evaluatedSwitch
2022-09-12 09:58:08 +02:00
jonny_ji7
38ad266488 Remove public handle func, add getState functions
switchesAnalog:
- Add functions for obtaining states from each switch
- Remove public handle function, (now run locally at each state request of
a pin)

- adjust main.cpp to work with new functions
2022-09-12 09:57:22 +02:00
jonny_ji7
a932460924 EvalSwitch: Add func as source, remove dupl code
evaluatedSwitch component:
- remove duplicate code for inverted and non-inverted mode
- add new constructor for instance with a function to obtain current
  input state instead of gpio pin (e.g. needed for 4switches on analog input)
2022-09-12 09:47:06 +02:00
jonny_ji7
09ee67f583 Add code for demuxing 4 switch signals from adc pin
- create new files with code for demultiplexing the 4 switches from the
  one analog signal
- define lookup table with measurements done with the build pcb, test
  switches and esp32 breakout board
- add note do config that gpio used for digital in is now used for
  this multiplexer
- main.cpp: disable control task, run new handle function in a loop for
  testing
2022-09-11 19:58:13 +02:00
jonny_ji7
f52a58aa1c Add schematic, layout, calculations for 4swToAdc
Add details and calculations for a stripboard with a resistor network that makes it
possible to connect 4 switches (to gnd) to one adc pin of the controller
2022-09-11 19:53:57 +02:00
jonny_ji7
7eb06fe228 Add wire-cutter to connection-plan and function-diagram 2022-09-04 11:56:32 +02:00
jonny_l480
5a3c6b15bc Merge branch 'display'
- merge display branch with outsourced and reworked display code
- resolve merge conflict caused by new ENCODER_TEST feature in main
2022-08-26 14:04:50 +02:00
jonny_l480
248668c526 Add encoder-test, calibrate distance conversion
Add encoder test:
  - used for calibrating the length measurement by counting the steps
    per meter
  - enabled with #define ENCODER_TEST  in config.hpp
  - display1: enocder steps
  - display2: converted length in meter

Distance conversion:
  - defining STEPS_PER_METER instead of MEASURING_ROLL_DIAMETER in
    config.hpp
  - defining the steps per meter by issuing 3 test measurements with
    4mm2 solar cable in the new encoder test mode
2022-08-26 13:24:51 +02:00
jonny_ji7
9d416d29e6 Switch from 7.5kw vfd to 700W vfd
Already switched earlier, now optimized code and connection plan to work
best with new vfd (T130750W).
Previous 7.5kw vfd will work too without using all 7 speed levels as at
first.

connection plan: changed pin assignment (1 free pin)

Code:
  - vfd.cpp, main.cpp: remove not used D2 pin (only used with 7.5kw vfd)
  - config.hpp: change pin assignment
2022-08-26 11:24:27 +02:00
jonny_ji7
070fd7069d Add msg on stop, start-target, Optimize logging 2022-08-26 11:10:55 +02:00
jonny_ji7
c1a12d93f0 Add blink method to display class
- Add method to trigger blinking of the display for a certain count and durations
  also with a optional off-string

- Add 3x blinking after applying a new target length with preset or set
  buttons
2022-08-23 12:29:15 +02:00
jonny_ji7
92f7299080 Disp: show manual lvl and dir, brightness, soll blink
- in manual mode blink between 'manual' and lvl+direction indication on
  display 2

- when setting custom target length only blink value not "soll"

- reduce brightness from 12 to 8 because of high display temperature
2022-08-23 12:29:06 +02:00
jonny_ji7
2e331d841d Revert "Show manual speed lvl; Change buf"
This reverts commit 4e2cc070d1.
Other approach for displaying manual speed lvl found
2022-08-22 22:37:23 +02:00
jonny_ji7
9f329101a1 Fix bug display lib: random characters flickering
Fix bug in display library where random chars were written to display even
though the array has ended.
Resulting in random character appearing briefly when only first display got written.

-> stop loop when 0-termination of char array is reached
2022-08-22 22:22:45 +02:00
jonny_ji7
4e2cc070d1 Show manual speed lvl; Change buf
- when in manual mode blink between 'manual' and motor 'lvl' on bottom
  display
- optimize buffer variables and sizes
2022-08-22 18:27:28 +02:00
jonny_ji7
586c335896 Create 'handledDisplay' class
To abstract rather complex functions for 7 segment displays e.g. blink text, scroll
text... a class was created.

This makes it possible to have 2 instances for displayTop and
displayBottom resulting in no duplicate code
2022-08-22 16:28:42 +02:00
jonny_ji7
6acf99d894 Merge branch 'main' into display 2022-08-21 20:48:35 +02:00
jonny_ji7
9665560bbb Add blink strings functionality
add functions to display.cpp
  - void display2_handle();
  - void display2_blinkStrings(const char * strOn, const char * strOff, uint32_t msOn, uint32_t msOff);

control.cpp:
  - blink target length when set button is pressed
  - blink MANUAL when in manual mode
2022-08-21 17:30:00 +02:00
jonny_l480
c8ffd94fe9 Fix bug spi init; Fix random string + flickering
Fix bug where sartup randomly crasehd several times because spi config
was initialized with random data -> init with 0

Fix bug where length now was not truncated resulting in flickerin

Fix bug in welcome message where hello string contained random data
2022-08-21 14:08:59 +02:00
jonny_l480
c5438b6c4c Fix bug custom length, add hyst; Adjust beeping
- Fix bug where custom length did not get rounded
- Reduce beeping lengths, remove gap between beep events
- Add hysteresis to custom length selection to prevent unwanted beeps or
flickering display at certain poti positions
- change max loglevel to verbose in menuconfig
2022-08-21 13:45:29 +02:00
jonny_ji7
01c5db39c1 Outsource display functions to display.cpp
move functions for initializing and writing to display to new files
display.cpp/hpp
2022-08-21 12:12:56 +02:00
jonny_ji7
b238e582cc Add dyn-speed to start state; Update function-diagram
- outsource dynamic speed to setDynSpeedLvl function
- reuse function in wind-slow state with limit

- update function diagram to representation of current program
2022-08-20 18:28:37 +02:00
jonny_ji7
ae41b93e63 Add preset buttons; Optimizations
- add functionality to set preset lengths with preset buttons

- change variables
- add/change comments
- reorder code
- add beeping at custom length selection
2022-08-20 17:54:23 +02:00
jonny_l480
5ddf8699e2 Change wheel diameter (larger wheel v3) 2022-08-20 14:17:40 +02:00
jonny_l480
8900da9113 Add speed lvl selection via poti in manual mode 2022-08-20 14:13:45 +02:00
jonny_l480
68f97644be Fix bugs MANUAL mode, Adjustments new VFD
fix bugs introduced with addition of manual mode:
    - fix stuck in target_reached state
    - fix bug switch to manual mode only in counting possible

new vfd
    - new 750W vfd has 1 speed select pin less -> limit used
      levels to 0-3
2022-08-20 14:00:51 +02:00
jonny_ji7
e9e1df9ea1 Change/Add sw pulldown resistors, Fix MANUAL mode
Analog In only pins have no internal pullup resistors.
thus two preset switches need pulldown resistors on pcb to be soldered
and switch to 3v instead of GND
- changed in connection plan
- changed switch config in config.cpp (no pullup, inverted)

Fix manual mode:
previously there was a bugged change loop when pressing all 3 buttons
- made mode switch more clear
2022-08-20 10:08:36 +02:00
jonny_ji7
dddd54b03a Add MANUAL mode, Add vfd direction support
vfd: extend vfd_setState function with direction enum (default fwd)
main: reduce log output from buzzer task
config: use mos1 as vfd_FWD output
control:
    add MANUAL state: motor can be controlled via preset buttons
    adjust code slightly to support new state (also see updated
    function-diagram)
2022-08-19 16:29:59 +02:00
jonny_ji7
f6b2093650 Update connection-plan, function-diagram
function diagram represents currently implemented control
connection plan:
    - add vfd reverse
    - optimizations, fixes
    - wire colors
    - 7 segment display wiring
2022-08-18 21:21:28 +02:00
jonny_l480
68dc012fcc Fix disabled encoder, scaling; Adjust intervals
test with actual hardware
encoder init was commented out
scaling was off by factor 600
adjust speed intervals
2022-08-18 15:31:46 +02:00
jonny_ji7
8b9b5ff736 Add control statemachine, optimize vfd logging
Add all logic for the machine to control.cpp
optimize logging (on change only) for vfd functions
2022-08-18 14:23:32 +02:00
jonny_ji7
0aea494783 Add poti and display section; Cleanup
Add readadc function from armchair project
Rework display section
   - show lengthNow on first display
   - show lengthTarget on second display
Prepare for statemachine

Remove unneeded function
Add comments improve structure
2022-08-18 12:46:08 +02:00
jonny_ji7
7ccde65893 Update function-diagram: SM, Buttons, Display
Create function diagram with all currently planned features
2022-08-18 12:44:28 +02:00
jonny_ji7
59bb48902d Add second 7-seg display, Welcome message
Add second display in series to first one
Adjust control.cpp
- welcome msg name. date
- scroll "hello" over two displays"
- display Ist/soll dummy text on each display
2022-08-18 09:48:29 +02:00
jonny_ji7
b68dae7e59 Swap vfd data pins, Update connection plan
Tested new vfd functions, encoder and display - works as intended now
2022-08-17 15:39:25 +02:00
jonny_ji7
7fae539f14 Add vfd driver, Add vfd test via buttons
Add vfd.cpp/hpp with functions to control the VFD via 4 digital pins
Add way to test the vfd via SET button (rotate speed level) and START
button (toggle motor on/off)
2022-08-17 14:05:34 +02:00
jonny_ji7
22f8aef8d2 Move code from main to control.cpp, display pages
- move code from testing task to control.cpp
- outsource functions for initializing display and encoder
- delete testing code
- add two display pages (current distance and counter)
- run handle functions for each button
2022-08-17 13:08:05 +02:00
jonny_ji7
739f5ef4c2 Add Readme, connection-plan, function-diagram
Readme:
    - component description

connection plan:
    - fully connected pcb
    - control panel overview with all input elements

function-diagram:
    - partial functions
2022-08-17 10:39:26 +02:00
jonny_ji7
a3f3cb340c Add config, buzzer, evalSwitch, switch to c++
Add config.cpp/hpp
    - macros for all input and output pins
    - gloabl evaluated switch objects
    - buzzer object
    - display config
    - encoder config

Move main.c to main.cpp and adjust code to be c++ compatible

add custom library evaluated switch (copied from armchair project)
add buzzer object (copied from armchair project)

add control.cpp/hpp with control task (no function yet)
2022-08-17 10:29:11 +02:00
32 changed files with 2585 additions and 197 deletions

3
.gitignore vendored
View File

@@ -4,3 +4,6 @@ build
# VIM files
*.swp
*.swo
# drawio files
*.bkp

18
README.md Normal file
View 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

View File

@@ -0,0 +1,6 @@
idf_component_register(
SRCS
"gpio_evaluateSwitch.cpp"
"gpio_adc.cpp"
INCLUDE_DIRS "."
)

View File

@@ -0,0 +1,21 @@
#include "gpio_adc.hpp"
//=============================
//========= readAdc ===========
//=============================
//function for multisampling an anlog input
int gpio_readAdc(adc1_channel_t adc_channel, bool inverted) {
//make multiple measurements
int adc_reading = 0;
for (int i = 0; i < 32; i++) {
adc_reading += adc1_get_raw(adc_channel);
}
adc_reading = adc_reading / 32;
//return original or inverted result
if (inverted) {
return 4095 - adc_reading;
} else {
return adc_reading;
}
}

View File

@@ -0,0 +1,9 @@
#pragma once
#include <stdio.h>
#include "driver/adc.h"
//function for multisampling an anlog input
//measures 30 times and returns average
//if invertion is used currently 11bit resolution is assumed (subtracts from 4095)
//TODO: rework this function to be more universal
int gpio_readAdc(adc1_channel_t adc_channel, bool inverted = false);

View File

@@ -0,0 +1,146 @@
#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;
inputSource = inputSource_t::GPIO;
initGpio();
};
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;
inputSource = inputSource_t::GPIO;
initGpio();
};
gpio_evaluatedSwitch::gpio_evaluatedSwitch( //with function as input source
bool (*getInputStatePtr_f)(void),
bool inverted_f){
//gpio_num = NULL;
//pullup = NULL;
inverted = inverted_f;
getInputStatePtr = getInputStatePtr_f;
inputSource = inputSource_t::FUNCTION;
};
void gpio_evaluatedSwitch::initGpio(){
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
//--- get pin state with required method ---
switch (inputSource){
case inputSource_t::GPIO: //from gpio pin
if (gpio_get_level(gpio_num) == 0){ //pin low
inputState = true;
} else { //pin high
inputState = false;
}
break;
case inputSource_t::FUNCTION: //from funtion
inputState = (*getInputStatePtr)();
break;
}
//--- invert state ---
//not inverted: switch switches to GND when active
//inverted: switch switched to VCC when active
if (inverted == true){
inputState = !inputState;
}
//=========================================================
//========= Statemachine for evaluateing switch ===========
//=========================================================
switch (p_state){
default:
p_state = switchState::FALSE;
break;
case switchState::FALSE: //input confirmed high (released)
fallingEdge = false; //reset edge event
if (inputState == true){ //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 (inputState == true){ //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 (inputState == false){ //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 (inputState == false){ //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;
}
}

View File

@@ -0,0 +1,71 @@
#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);
enum class inputSource_t {GPIO, FUNCTION};
class gpio_evaluatedSwitch {
public:
//--- input ---
uint32_t minOnMs = 30;
uint32_t minOffMs = 30;
//constructor minimal (default parameters pullup=true, inverted=false)
gpio_evaluatedSwitch(
gpio_num_t gpio_num_declare
);
//constructor with optional parameters
gpio_evaluatedSwitch(
gpio_num_t gpio_num_declare,
bool pullup_declare,
bool inverted_declare=false
);
//constructor with a function as source for input state instead of a gpio pin
gpio_evaluatedSwitch(bool (*getInputStatePtr_f)(void), bool inverted_f=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;
bool (*getInputStatePtr)(void); //pointer to function for getting current input state
inputSource_t inputSource = inputSource_t::GPIO;
enum class switchState {TRUE, FALSE, LOW, HIGH};
switchState p_state = switchState::FALSE;
bool inputState = false;
uint32_t timestampLow = 0;
uint32_t timestampHigh = 0;
void initGpio();
};

View File

@@ -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

File diff suppressed because one or more lines are too long

BIN
connection-plan.drawio.pdf Normal file

Binary file not shown.

1
function-diagram.drawio Normal file

File diff suppressed because one or more lines are too long

BIN
function-diagram.drawio.pdf Normal file

Binary file not shown.

View File

@@ -1,2 +1,12 @@
idf_component_register(SRCS "main.c"
INCLUDE_DIRS ".")
idf_component_register(
SRCS
"main.cpp"
"config.cpp"
"control.cpp"
"buzzer.cpp"
"vfd.cpp"
"display.cpp"
"switchesAnalog.cpp"
INCLUDE_DIRS
"."
)

98
main/buzzer.cpp Normal file
View 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
View 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;
};

21
main/config.cpp Normal file
View File

@@ -0,0 +1,21 @@
#include "config.hpp"
//--- inputs ---
//create and configure objects for evaluated switches
//gpio_evaluatedSwitch sw_gpio_39(GPIO_NUM_39, false, true); //pullup false, INVERTED (switch to 3V3, pulldown on pcb soldered)
gpio_evaluatedSwitch sw_gpio_34(GPIO_NUM_34, false, true); //pullup false, INVERTED (switch to 3V3, pulldown on pcb soldered)
gpio_evaluatedSwitch sw_gpio_32(GPIO_NUM_32, true, false); //pullup true, not inverted (switch to GND, internal pullup used)
gpio_evaluatedSwitch sw_gpio_33(GPIO_NUM_33, true, false); //pullup true, not inverted (switch to GND, internal pullup used)
gpio_evaluatedSwitch sw_gpio_25(GPIO_NUM_25, true, false); //pullup true, not inverted (switch to GND, internal pullup used)
gpio_evaluatedSwitch sw_gpio_26(GPIO_NUM_26, true, false); //pullup true, not inverted (switch to GND, internal pullup used)
//--- switches connected to 4 sw to analog stripboard ---
//evaluated switches with function to obtain the current input state instead of gpio
gpio_evaluatedSwitch sw_gpio_analog_0(&switchesAnalog_getState_sw0);
gpio_evaluatedSwitch sw_gpio_analog_1(&switchesAnalog_getState_sw1);
gpio_evaluatedSwitch sw_gpio_analog_2(&switchesAnalog_getState_sw2);
gpio_evaluatedSwitch sw_gpio_analog_3(&switchesAnalog_getState_sw3);
//create buzzer object with no gap between beep events
buzzer_t buzzer(GPIO_BUZZER, 0);

109
main/config.hpp Normal file
View File

@@ -0,0 +1,109 @@
#pragma once
extern "C" {
#include "driver/adc.h"
}
#include "gpio_evaluateSwitch.hpp"
#include "buzzer.hpp"
#include "switchesAnalog.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 analog input pins ====
//==================================
#define GPIO_POTI GPIO_NUM_36
#define ADC_CHANNEL_POTI ADC1_CHANNEL_0
#define GPIO_4SW_TO_ANALOG GPIO_NUM_39
#define ADC_CHANNEL_4SW_TO_ANALOG ADC1_CHANNEL_3 //gpio 39
//ADC1_CHANNEL_0 gpio36
//ADC1_CHANNEL_6 gpio_34
//ADC1_CHANNEL_3 gpio_39
//=====================================
//==== assign switches to objects =====
//=====================================
//see config.cpp for available evaluated switch objects
#define SW_START sw_gpio_26
#define SW_RESET sw_gpio_25
#define SW_SET sw_gpio_analog_0
#define SW_PRESET1 sw_gpio_analog_1
#define SW_PRESET2 sw_gpio_analog_2
#define SW_PRESET3 sw_gpio_analog_3
//unused but already available evaluated inputs
//#define ? sw_gpio_33
//#define ? sw_gpio_32
//#define ? sw_gpio_34
//--------------------------
//----- 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
//--- switches on digital gpio pins ---
//extern gpio_evaluatedSwitch sw_gpio_39;
extern gpio_evaluatedSwitch sw_gpio_34;
extern gpio_evaluatedSwitch sw_gpio_32;
extern gpio_evaluatedSwitch sw_gpio_33;
extern gpio_evaluatedSwitch sw_gpio_25;
extern gpio_evaluatedSwitch sw_gpio_26;
//--- switches connected to 4-sw-to-analog stripboard ---
extern gpio_evaluatedSwitch sw_gpio_analog_0;
extern gpio_evaluatedSwitch sw_gpio_analog_1;
extern gpio_evaluatedSwitch sw_gpio_analog_2;
extern gpio_evaluatedSwitch sw_gpio_analog_3;
//create global buzzer object
extern buzzer_t buzzer;

407
main/control.cpp Normal file
View File

@@ -0,0 +1,407 @@
#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;
}
//====================
//==== 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 = gpio_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 = gpio_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
}
}

32
main/control.hpp Normal file
View File

@@ -0,0 +1,32 @@
#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 "gpio_adc.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
View 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
View 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;
};

View File

@@ -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);
}

94
main/main.cpp Normal file
View File

@@ -0,0 +1,94 @@
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"
#include "switchesAnalog.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("switches-analog", ESP_LOG_WARN);
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);
}

103
main/switchesAnalog.cpp Normal file
View File

@@ -0,0 +1,103 @@
#include "switchesAnalog.hpp"
#define CHECK_BIT(var,pos) (((var)>>(pos)) & 1) //TODO duplicate code: same macro already used in vfd.cpp
//=====================
//===== Variables =====
//=====================
static const char *TAG = "switches-analog"; //tag for logging
int diffMin = 4095;
int adcValue;
int match_index = 0;
//array that describes voltages for all combinations of the 4 inputs
const int lookup_voltages[] = {
//ADC, S3 S2 S1 S0
4095, //0000
3780, //0001
3390, //0010
3040, //0011
2760, //0100
2542, //0101
2395, //0110
2225, //0111
1964, //1000
1845, //1001
1762, //1010
1664, //1011
1573, //1100
1485, //1101
1432, //1110
1363 //1111
};
//===========================
//===== handle function =====
//===========================
//handle demuxing of 4 switches from 1 adc (has to be run repeatedly)
void handle(){
//read current voltage
adcValue = gpio_readAdc(ADC_CHANNEL_4SW_TO_ANALOG);
ESP_LOGI(TAG, "voltage read: %d", adcValue);
//find closest match in lookup table
diffMin = 4095; //reset diffMin each run
for (int i=0; i<16; i++){
int diff = fabs(adcValue - lookup_voltages[i]);
if (diff < diffMin){
diffMin = diff;
match_index = i;
}
}
//get bool values for each input from matched index
bool s0 = CHECK_BIT(match_index, 0);
bool s1 = CHECK_BIT(match_index, 1);
bool s2 = CHECK_BIT(match_index, 2);
bool s3 = CHECK_BIT(match_index, 3);
//bool s1 = ((match_index & 0b1000) == 0b1000);
//bool s2 = ((match_index & 0b0100) == 0b0100);
//bool s3 = ((match_index & 0b0010) == 0b0010);
//bool s4 = ((match_index & 0b0001) == 0b0001);
//log results
ESP_LOGI(TAG, "adcRead: %d, closest-match: %d, diff: %d, index: %d, switches: %d%d%d%d",
adcValue, lookup_voltages[match_index], diffMin, match_index, (int)s3, (int)s2, (int)s1, (int)s0);
}
//====================
//===== getState =====
//====================
//get state of certain switch (0-3)
bool switchesAnalog_getState(int swNumber){
//run handle function to obtain all current input states
handle();
//get relevant bit
bool state = CHECK_BIT(match_index, swNumber);
ESP_LOGI(TAG, "returned state of switch No. %d = %i", swNumber, (int)state);
return state;
}
bool switchesAnalog_getState_sw0(){
return switchesAnalog_getState(0);
}
bool switchesAnalog_getState_sw1(){
return switchesAnalog_getState(1);
}
bool switchesAnalog_getState_sw2(){
return switchesAnalog_getState(2);
}
bool switchesAnalog_getState_sw3(){
return switchesAnalog_getState(3);
}

21
main/switchesAnalog.hpp Normal file
View File

@@ -0,0 +1,21 @@
#pragma once
extern "C"
{
#include <stdio.h>
#include <freertos/FreeRTOS.h>
#include "esp_log.h"
#include "driver/adc.h"
#include <math.h>
}
#include "config.hpp"
#include "gpio_adc.hpp"
//get current state of certain switch
bool switchesAnalog_getState(int swNumber);
bool switchesAnalog_getState_sw0();
bool switchesAnalog_getState_sw1();
bool switchesAnalog_getState_sw2();
bool switchesAnalog_getState_sw3();

116
main/vfd.cpp Normal file
View 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
View 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);

75
pcb/4swToAdc.kicad_prl Normal file
View File

@@ -0,0 +1,75 @@
{
"board": {
"active_layer": 0,
"active_layer_preset": "",
"auto_track_width": true,
"hidden_nets": [],
"high_contrast_mode": 0,
"net_color_mode": 1,
"opacity": {
"pads": 1.0,
"tracks": 1.0,
"vias": 1.0,
"zones": 0.6
},
"ratsnest_display_mode": 0,
"selection_filter": {
"dimensions": true,
"footprints": true,
"graphics": true,
"keepouts": true,
"lockedItems": true,
"otherItems": true,
"pads": true,
"text": true,
"tracks": true,
"vias": true,
"zones": true
},
"visible_items": [
0,
1,
2,
3,
4,
5,
8,
9,
10,
11,
12,
13,
14,
15,
16,
17,
18,
19,
20,
21,
22,
23,
24,
25,
26,
27,
28,
29,
30,
32,
33,
34,
35,
36
],
"visible_layers": "fffffff_ffffffff",
"zone_display_mode": 0
},
"meta": {
"filename": "4-switches-to-adc.kicad_prl",
"version": 3
},
"project": {
"files": []
}
}

294
pcb/4swToAdc.kicad_pro Normal file
View File

@@ -0,0 +1,294 @@
{
"board": {
"layer_presets": []
},
"boards": [],
"cvpcb": {
"equivalence_files": []
},
"erc": {
"erc_exclusions": [],
"meta": {
"version": 0
},
"pin_map": [
[
0,
0,
0,
0,
0,
0,
1,
0,
0,
0,
0,
2
],
[
0,
2,
0,
1,
0,
0,
1,
0,
2,
2,
2,
2
],
[
0,
0,
0,
0,
0,
0,
1,
0,
1,
0,
1,
2
],
[
0,
1,
0,
0,
0,
0,
1,
1,
2,
1,
1,
2
],
[
0,
0,
0,
0,
0,
0,
1,
0,
0,
0,
0,
2
],
[
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
2
],
[
1,
1,
1,
1,
1,
0,
1,
1,
1,
1,
1,
2
],
[
0,
0,
0,
1,
0,
0,
1,
0,
0,
0,
0,
2
],
[
0,
2,
1,
2,
0,
0,
1,
0,
2,
2,
2,
2
],
[
0,
2,
0,
1,
0,
0,
1,
0,
2,
0,
0,
2
],
[
0,
2,
1,
1,
0,
0,
1,
0,
2,
0,
0,
2
],
[
2,
2,
2,
2,
2,
2,
2,
2,
2,
2,
2,
2
]
],
"rule_severities": {
"bus_definition_conflict": "error",
"bus_entry_needed": "error",
"bus_label_syntax": "error",
"bus_to_bus_conflict": "error",
"bus_to_net_conflict": "error",
"different_unit_footprint": "error",
"different_unit_net": "error",
"duplicate_reference": "error",
"duplicate_sheet_names": "error",
"extra_units": "error",
"global_label_dangling": "warning",
"hier_label_mismatch": "error",
"label_dangling": "error",
"lib_symbol_issues": "warning",
"multiple_net_names": "warning",
"net_not_bus_member": "warning",
"no_connect_connected": "warning",
"no_connect_dangling": "warning",
"pin_not_connected": "error",
"pin_not_driven": "error",
"pin_to_pin": "warning",
"power_pin_not_driven": "error",
"similar_labels": "warning",
"unannotated": "error",
"unit_value_mismatch": "error",
"unresolved_variable": "error",
"wire_dangling": "error"
}
},
"libraries": {
"pinned_footprint_libs": [],
"pinned_symbol_libs": []
},
"meta": {
"filename": "4-switches-to-adc.kicad_pro",
"version": 1
},
"net_settings": {
"classes": [
{
"bus_width": 12.0,
"clearance": 0.2,
"diff_pair_gap": 0.25,
"diff_pair_via_gap": 0.25,
"diff_pair_width": 0.2,
"line_style": 0,
"microvia_diameter": 0.3,
"microvia_drill": 0.1,
"name": "Default",
"pcb_color": "rgba(0, 0, 0, 0.000)",
"schematic_color": "rgba(0, 0, 0, 0.000)",
"track_width": 0.25,
"via_diameter": 0.8,
"via_drill": 0.4,
"wire_width": 6.0
}
],
"meta": {
"version": 2
},
"net_colors": null
},
"pcbnew": {
"last_paths": {
"gencad": "",
"idf": "",
"netlist": "",
"specctra_dsn": "",
"step": "",
"vrml": ""
},
"page_layout_descr_file": ""
},
"schematic": {
"annotate_start_num": 0,
"drawing": {
"default_line_thickness": 6.0,
"default_text_size": 50.0,
"field_names": [],
"intersheets_ref_own_page": false,
"intersheets_ref_prefix": "",
"intersheets_ref_short": false,
"intersheets_ref_show": false,
"intersheets_ref_suffix": "",
"junction_size_choice": 3,
"label_size_ratio": 0.375,
"pin_symbol_size": 25.0,
"text_offset_ratio": 0.15
},
"legacy_lib_dir": "",
"legacy_lib_list": [],
"meta": {
"version": 1
},
"net_format_name": "",
"page_layout_descr_file": "",
"plot_directory": "",
"spice_adjust_passive_values": false,
"spice_external_command": "spice \"%I\"",
"subpart_first_id": 65,
"subpart_id_separator": 0
},
"sheets": [
[
"0534e379-8bf0-4abf-a148-fc91b6440529",
""
]
],
"text_variables": {}
}

580
pcb/4swToAdc.kicad_sch Normal file
View File

@@ -0,0 +1,580 @@
(kicad_sch (version 20211123) (generator eeschema)
(uuid 0534e379-8bf0-4abf-a148-fc91b6440529)
(paper "A4")
(lib_symbols
(symbol "Device:R" (pin_numbers hide) (pin_names (offset 0)) (in_bom yes) (on_board yes)
(property "Reference" "R" (id 0) (at 2.032 0 90)
(effects (font (size 1.27 1.27)))
)
(property "Value" "R" (id 1) (at 0 0 90)
(effects (font (size 1.27 1.27)))
)
(property "Footprint" "" (id 2) (at -1.778 0 90)
(effects (font (size 1.27 1.27)) hide)
)
(property "Datasheet" "~" (id 3) (at 0 0 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "ki_keywords" "R res resistor" (id 4) (at 0 0 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "ki_description" "Resistor" (id 5) (at 0 0 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "ki_fp_filters" "R_*" (id 6) (at 0 0 0)
(effects (font (size 1.27 1.27)) hide)
)
(symbol "R_0_1"
(rectangle (start -1.016 -2.54) (end 1.016 2.54)
(stroke (width 0.254) (type default) (color 0 0 0 0))
(fill (type none))
)
)
(symbol "R_1_1"
(pin passive line (at 0 3.81 270) (length 1.27)
(name "~" (effects (font (size 1.27 1.27))))
(number "1" (effects (font (size 1.27 1.27))))
)
(pin passive line (at 0 -3.81 90) (length 1.27)
(name "~" (effects (font (size 1.27 1.27))))
(number "2" (effects (font (size 1.27 1.27))))
)
)
)
(symbol "Switch:SW_Push" (pin_numbers hide) (pin_names (offset 1.016) hide) (in_bom yes) (on_board yes)
(property "Reference" "SW" (id 0) (at 1.27 2.54 0)
(effects (font (size 1.27 1.27)) (justify left))
)
(property "Value" "SW_Push" (id 1) (at 0 -1.524 0)
(effects (font (size 1.27 1.27)))
)
(property "Footprint" "" (id 2) (at 0 5.08 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "Datasheet" "~" (id 3) (at 0 5.08 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "ki_keywords" "switch normally-open pushbutton push-button" (id 4) (at 0 0 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "ki_description" "Push button switch, generic, two pins" (id 5) (at 0 0 0)
(effects (font (size 1.27 1.27)) hide)
)
(symbol "SW_Push_0_1"
(circle (center -2.032 0) (radius 0.508)
(stroke (width 0) (type default) (color 0 0 0 0))
(fill (type none))
)
(polyline
(pts
(xy 0 1.27)
(xy 0 3.048)
)
(stroke (width 0) (type default) (color 0 0 0 0))
(fill (type none))
)
(polyline
(pts
(xy 2.54 1.27)
(xy -2.54 1.27)
)
(stroke (width 0) (type default) (color 0 0 0 0))
(fill (type none))
)
(circle (center 2.032 0) (radius 0.508)
(stroke (width 0) (type default) (color 0 0 0 0))
(fill (type none))
)
(pin passive line (at -5.08 0 0) (length 2.54)
(name "1" (effects (font (size 1.27 1.27))))
(number "1" (effects (font (size 1.27 1.27))))
)
(pin passive line (at 5.08 0 180) (length 2.54)
(name "2" (effects (font (size 1.27 1.27))))
(number "2" (effects (font (size 1.27 1.27))))
)
)
)
(symbol "power:+3V3" (power) (pin_names (offset 0)) (in_bom yes) (on_board yes)
(property "Reference" "#PWR" (id 0) (at 0 -3.81 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "Value" "+3V3" (id 1) (at 0 3.556 0)
(effects (font (size 1.27 1.27)))
)
(property "Footprint" "" (id 2) (at 0 0 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "Datasheet" "" (id 3) (at 0 0 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "ki_keywords" "power-flag" (id 4) (at 0 0 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "ki_description" "Power symbol creates a global label with name \"+3V3\"" (id 5) (at 0 0 0)
(effects (font (size 1.27 1.27)) hide)
)
(symbol "+3V3_0_1"
(polyline
(pts
(xy -0.762 1.27)
(xy 0 2.54)
)
(stroke (width 0) (type default) (color 0 0 0 0))
(fill (type none))
)
(polyline
(pts
(xy 0 0)
(xy 0 2.54)
)
(stroke (width 0) (type default) (color 0 0 0 0))
(fill (type none))
)
(polyline
(pts
(xy 0 2.54)
(xy 0.762 1.27)
)
(stroke (width 0) (type default) (color 0 0 0 0))
(fill (type none))
)
)
(symbol "+3V3_1_1"
(pin power_in line (at 0 0 90) (length 0) hide
(name "+3V3" (effects (font (size 1.27 1.27))))
(number "1" (effects (font (size 1.27 1.27))))
)
)
)
(symbol "power:GND" (power) (pin_names (offset 0)) (in_bom yes) (on_board yes)
(property "Reference" "#PWR" (id 0) (at 0 -6.35 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "Value" "GND" (id 1) (at 0 -3.81 0)
(effects (font (size 1.27 1.27)))
)
(property "Footprint" "" (id 2) (at 0 0 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "Datasheet" "" (id 3) (at 0 0 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "ki_keywords" "power-flag" (id 4) (at 0 0 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "ki_description" "Power symbol creates a global label with name \"GND\" , ground" (id 5) (at 0 0 0)
(effects (font (size 1.27 1.27)) hide)
)
(symbol "GND_0_1"
(polyline
(pts
(xy 0 0)
(xy 0 -1.27)
(xy 1.27 -1.27)
(xy 0 -2.54)
(xy -1.27 -1.27)
(xy 0 -1.27)
)
(stroke (width 0) (type default) (color 0 0 0 0))
(fill (type none))
)
)
(symbol "GND_1_1"
(pin power_in line (at 0 0 270) (length 0) hide
(name "GND" (effects (font (size 1.27 1.27))))
(number "1" (effects (font (size 1.27 1.27))))
)
)
)
)
(junction (at 48.26 87.63) (diameter 0) (color 0 0 0 0)
(uuid 0595abd2-5372-4996-8c85-ea8e7ba6eaf5)
)
(junction (at 48.26 57.15) (diameter 0) (color 0 0 0 0)
(uuid 376c3252-bee9-4eae-8c35-3e8d8aea79a1)
)
(junction (at 60.96 57.15) (diameter 0) (color 0 0 0 0)
(uuid 37f07ef8-0bd0-4983-9e87-070da97b8027)
)
(junction (at 60.96 87.63) (diameter 0) (color 0 0 0 0)
(uuid b858a0b2-392b-42b8-814d-97eec6d10cf5)
)
(junction (at 73.66 57.15) (diameter 0) (color 0 0 0 0)
(uuid caf3ed74-8f3c-4ea2-9837-cc564ece24fc)
)
(junction (at 86.36 57.15) (diameter 0) (color 0 0 0 0)
(uuid e422a210-4268-4494-969d-097a39cbc71b)
)
(junction (at 73.66 87.63) (diameter 0) (color 0 0 0 0)
(uuid f688351c-21fd-46ff-a90d-cc366df00758)
)
(wire (pts (xy 60.96 57.15) (xy 60.96 60.325))
(stroke (width 0) (type default) (color 0 0 0 0))
(uuid 04af43fa-9f39-49fa-af8f-f49b7bc05656)
)
(wire (pts (xy 60.96 84.455) (xy 60.96 87.63))
(stroke (width 0) (type default) (color 0 0 0 0))
(uuid 0540396a-1bc2-4b04-906e-7d83c6b66195)
)
(wire (pts (xy 48.26 87.63) (xy 48.26 92.075))
(stroke (width 0) (type default) (color 0 0 0 0))
(uuid 1787faca-1557-4d40-a0c4-911d17f0770d)
)
(wire (pts (xy 86.36 67.945) (xy 86.36 74.295))
(stroke (width 0) (type default) (color 0 0 0 0))
(uuid 23b2ab5f-bdf4-4212-b143-bb49653e1b88)
)
(wire (pts (xy 48.26 57.15) (xy 48.26 60.325))
(stroke (width 0) (type default) (color 0 0 0 0))
(uuid 25a6a709-3fde-41fe-9a0e-cb508d73834a)
)
(wire (pts (xy 73.66 84.455) (xy 73.66 87.63))
(stroke (width 0) (type default) (color 0 0 0 0))
(uuid 2bc4885e-1811-40f7-9a6d-34ed596c1add)
)
(wire (pts (xy 48.26 41.275) (xy 48.26 45.085))
(stroke (width 0) (type default) (color 0 0 0 0))
(uuid 2c7d8342-fe94-4a1b-baec-58cd6c3eeca7)
)
(wire (pts (xy 48.26 67.945) (xy 48.26 74.295))
(stroke (width 0) (type default) (color 0 0 0 0))
(uuid 45921a4d-adb5-4631-b0f7-53468659bc65)
)
(wire (pts (xy 73.66 87.63) (xy 60.96 87.63))
(stroke (width 0) (type default) (color 0 0 0 0))
(uuid 480fea58-4754-4988-b652-79892cbd4343)
)
(polyline (pts (xy 38.1 33.02) (xy 110.49 33.02))
(stroke (width 0) (type default) (color 0 0 0 0))
(uuid 4d5b9ff9-ca59-4c44-bce2-c776250d20c0)
)
(wire (pts (xy 60.96 87.63) (xy 48.26 87.63))
(stroke (width 0) (type default) (color 0 0 0 0))
(uuid 5f8390d2-5874-477d-abd8-600f48800de1)
)
(wire (pts (xy 73.66 57.15) (xy 73.66 60.325))
(stroke (width 0) (type default) (color 0 0 0 0))
(uuid 689d4ae4-8fb6-467c-812a-f8189081bfa8)
)
(wire (pts (xy 60.96 57.15) (xy 48.26 57.15))
(stroke (width 0) (type default) (color 0 0 0 0))
(uuid 69ba96dd-74a8-4f3b-85f6-a998f64b3b7e)
)
(wire (pts (xy 86.36 87.63) (xy 73.66 87.63))
(stroke (width 0) (type default) (color 0 0 0 0))
(uuid 76bc9488-bd39-4e7f-ba21-8968e45bafbd)
)
(polyline (pts (xy 38.1 102.87) (xy 110.49 102.87))
(stroke (width 0) (type default) (color 0 0 0 0))
(uuid 8fda66e6-cca3-4608-bf63-d40d2a979623)
)
(wire (pts (xy 86.36 60.325) (xy 86.36 57.15))
(stroke (width 0) (type default) (color 0 0 0 0))
(uuid 92724cbb-f787-4755-8c00-fdaff5e7ac81)
)
(wire (pts (xy 86.36 57.15) (xy 92.71 57.15))
(stroke (width 0) (type default) (color 0 0 0 0))
(uuid 937bec40-8b53-4b31-acdc-755c933ec2ac)
)
(wire (pts (xy 48.26 52.705) (xy 48.26 57.15))
(stroke (width 0) (type default) (color 0 0 0 0))
(uuid 9a9c3b93-5397-4f20-8b92-a2c37f8c1874)
)
(wire (pts (xy 86.36 57.15) (xy 73.66 57.15))
(stroke (width 0) (type default) (color 0 0 0 0))
(uuid 9c65a4d5-2a36-456c-8138-19c6cad951eb)
)
(wire (pts (xy 60.96 67.945) (xy 60.96 74.295))
(stroke (width 0) (type default) (color 0 0 0 0))
(uuid a02e604e-10c2-4767-a22d-4a461b77881e)
)
(polyline (pts (xy 38.1 33.655) (xy 38.1 102.87))
(stroke (width 0) (type default) (color 0 0 0 0))
(uuid a2c30be3-07c7-4998-a3ab-a45d0d1aa278)
)
(wire (pts (xy 73.66 57.15) (xy 60.96 57.15))
(stroke (width 0) (type default) (color 0 0 0 0))
(uuid acd9d380-e80b-4364-af24-ac27f88537b5)
)
(wire (pts (xy 73.66 67.945) (xy 73.66 74.295))
(stroke (width 0) (type default) (color 0 0 0 0))
(uuid c5dfc4f2-d3c5-4fe8-81cc-954989ded559)
)
(wire (pts (xy 86.36 84.455) (xy 86.36 87.63))
(stroke (width 0) (type default) (color 0 0 0 0))
(uuid e013a703-8a26-45b6-b9ca-6cd0b0a9ceef)
)
(wire (pts (xy 48.26 84.455) (xy 48.26 87.63))
(stroke (width 0) (type default) (color 0 0 0 0))
(uuid e3a717ef-7fbb-42fd-bed3-8552fcbf95b5)
)
(polyline (pts (xy 110.49 102.87) (xy 110.49 33.02))
(stroke (width 0) (type default) (color 0 0 0 0))
(uuid f442d4ab-f8ba-49f9-b732-68585ed0f198)
)
(text "Stripboard\n4 switches to 1 analog input" (at 78.74 38.735 0)
(effects (font (size 1.27 1.27) (thickness 0.254) bold) (justify left bottom))
(uuid c525c9cc-a4a1-4f6e-a0cf-a2cc3419b679)
)
(global_label "esp32 ADC" (shape input) (at 92.71 57.15 0) (fields_autoplaced)
(effects (font (size 1.27 1.27)) (justify left))
(uuid b8dbce7d-0a95-4573-b764-9e68bdd24326)
(property "Intersheet References" "${INTERSHEET_REFS}" (id 0) (at 105.4041 57.0706 0)
(effects (font (size 1.27 1.27)) (justify left) hide)
)
)
(symbol (lib_id "power:GND") (at 48.26 92.075 0) (unit 1)
(in_bom yes) (on_board yes) (fields_autoplaced)
(uuid 07a9d758-a267-455f-b30c-3770f3527e7a)
(property "Reference" "#PWR?" (id 0) (at 48.26 98.425 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "Value" "GND" (id 1) (at 48.26 97.155 0))
(property "Footprint" "" (id 2) (at 48.26 92.075 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "Datasheet" "" (id 3) (at 48.26 92.075 0)
(effects (font (size 1.27 1.27)) hide)
)
(pin "1" (uuid e41399a7-f60b-4a80-a126-be056cb007e9))
)
(symbol (lib_id "Switch:SW_Push") (at 60.96 79.375 90) (unit 1)
(in_bom yes) (on_board yes) (fields_autoplaced)
(uuid 28a1ca96-47e6-44c9-b9dc-c435e73ae941)
(property "Reference" "SW2" (id 0) (at 62.23 79.3749 90)
(effects (font (size 1.27 1.27)) (justify right))
)
(property "Value" "SW_Push" (id 1) (at 62.23 80.6449 90)
(effects (font (size 1.27 1.27)) (justify right) hide)
)
(property "Footprint" "" (id 2) (at 55.88 79.375 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "Datasheet" "~" (id 3) (at 55.88 79.375 0)
(effects (font (size 1.27 1.27)) hide)
)
(pin "1" (uuid 8b2bb3c1-68dc-4a33-bbda-8e3f735cb89c))
(pin "2" (uuid 19313efc-c6f8-4165-9f12-2f4d196a0916))
)
(symbol (lib_id "Switch:SW_Push") (at 86.36 79.375 90) (unit 1)
(in_bom yes) (on_board yes) (fields_autoplaced)
(uuid 3742357e-3d4f-4d99-8094-756d8329e07a)
(property "Reference" "SW0" (id 0) (at 87.63 79.3749 90)
(effects (font (size 1.27 1.27)) (justify right))
)
(property "Value" "SW_Push" (id 1) (at 87.63 80.6449 90)
(effects (font (size 1.27 1.27)) (justify right) hide)
)
(property "Footprint" "" (id 2) (at 81.28 79.375 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "Datasheet" "~" (id 3) (at 81.28 79.375 0)
(effects (font (size 1.27 1.27)) hide)
)
(pin "1" (uuid ed19ccea-334b-4c85-8502-092081da9b5f))
(pin "2" (uuid 2f87aad1-080c-4cf8-9298-8cf8962ebf0b))
)
(symbol (lib_id "Device:R") (at 48.26 48.895 0) (unit 1)
(in_bom yes) (on_board yes) (fields_autoplaced)
(uuid 6eeba788-57b9-45a8-981d-ecd17efd1d54)
(property "Reference" "R_up" (id 0) (at 50.8 47.6249 0)
(effects (font (size 1.27 1.27)) (justify left))
)
(property "Value" "1k" (id 1) (at 50.8 50.1649 0)
(effects (font (size 1.27 1.27)) (justify left))
)
(property "Footprint" "" (id 2) (at 46.482 48.895 90)
(effects (font (size 1.27 1.27)) hide)
)
(property "Datasheet" "~" (id 3) (at 48.26 48.895 0)
(effects (font (size 1.27 1.27)) hide)
)
(pin "1" (uuid a7fb192a-733f-4bea-a1d7-a207050754dc))
(pin "2" (uuid 76ba5816-0ef3-41eb-80a7-15d3d0d4102f))
)
(symbol (lib_id "Device:R") (at 48.26 64.135 0) (unit 1)
(in_bom yes) (on_board yes)
(uuid 769febe6-b95c-4d37-94fa-e3721ea908aa)
(property "Reference" "R3" (id 0) (at 50.8 62.8649 0)
(effects (font (size 1.27 1.27)) (justify left))
)
(property "Value" "1k" (id 1) (at 50.8 65.4049 0)
(effects (font (size 1.27 1.27)) (justify left))
)
(property "Footprint" "" (id 2) (at 46.482 64.135 90)
(effects (font (size 1.27 1.27)) hide)
)
(property "Datasheet" "~" (id 3) (at 48.26 64.135 0)
(effects (font (size 1.27 1.27)) hide)
)
(pin "1" (uuid f91d18bf-da3d-43fe-8b9a-c8f17a1ef730))
(pin "2" (uuid 0e5a0907-c70d-45b4-9b1e-755718f7bf45))
)
(symbol (lib_id "Switch:SW_Push") (at 48.26 79.375 90) (unit 1)
(in_bom yes) (on_board yes)
(uuid 864b1f85-f995-433a-9a94-7965edbddf3c)
(property "Reference" "SW3" (id 0) (at 49.53 79.375 90)
(effects (font (size 1.27 1.27)) (justify right))
)
(property "Value" "SW_Push" (id 1) (at 49.53 80.6449 90)
(effects (font (size 1.27 1.27)) (justify right) hide)
)
(property "Footprint" "" (id 2) (at 43.18 79.375 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "Datasheet" "~" (id 3) (at 43.18 79.375 0)
(effects (font (size 1.27 1.27)) hide)
)
(pin "1" (uuid ddb4c830-ad05-4916-ada4-5d3ceca231c4))
(pin "2" (uuid 1b4f3986-79e7-4778-acb7-b047f55e11e8))
)
(symbol (lib_id "Device:R") (at 60.96 64.135 0) (unit 1)
(in_bom yes) (on_board yes) (fields_autoplaced)
(uuid 8c50ab84-72ab-438d-a9f1-a710a33b8e06)
(property "Reference" "R2" (id 0) (at 63.5 62.8649 0)
(effects (font (size 1.27 1.27)) (justify left))
)
(property "Value" "2k2" (id 1) (at 63.5 65.4049 0)
(effects (font (size 1.27 1.27)) (justify left))
)
(property "Footprint" "" (id 2) (at 59.182 64.135 90)
(effects (font (size 1.27 1.27)) hide)
)
(property "Datasheet" "~" (id 3) (at 60.96 64.135 0)
(effects (font (size 1.27 1.27)) hide)
)
(pin "1" (uuid c171a640-9d38-495e-a5d9-7d8f95ea6fee))
(pin "2" (uuid 5e366793-5e2a-4a8a-ba3c-8de861c6f28d))
)
(symbol (lib_id "Switch:SW_Push") (at 73.66 79.375 90) (unit 1)
(in_bom yes) (on_board yes) (fields_autoplaced)
(uuid 93d3db7a-9c33-4a6b-8a4f-9c98164fe8b8)
(property "Reference" "SW1" (id 0) (at 74.93 79.3749 90)
(effects (font (size 1.27 1.27)) (justify right))
)
(property "Value" "SW_Push" (id 1) (at 74.93 80.6449 90)
(effects (font (size 1.27 1.27)) (justify right) hide)
)
(property "Footprint" "" (id 2) (at 68.58 79.375 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "Datasheet" "~" (id 3) (at 68.58 79.375 0)
(effects (font (size 1.27 1.27)) hide)
)
(pin "1" (uuid 5f3464d1-5065-4af5-a2f2-3aa2e6eda618))
(pin "2" (uuid bd5f3ec3-2c19-4b99-96ae-a4b755f1a5e1))
)
(symbol (lib_id "power:+3V3") (at 48.26 41.275 0) (unit 1)
(in_bom yes) (on_board yes) (fields_autoplaced)
(uuid a516e0a9-fe24-4120-873c-6f89d1fb49c0)
(property "Reference" "#PWR?" (id 0) (at 48.26 45.085 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "Value" "+3V3" (id 1) (at 48.26 36.195 0))
(property "Footprint" "" (id 2) (at 48.26 41.275 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "Datasheet" "" (id 3) (at 48.26 41.275 0)
(effects (font (size 1.27 1.27)) hide)
)
(pin "1" (uuid 7edde932-e6ea-4bb3-80d2-0dfb0b34dfdf))
)
(symbol (lib_id "Device:R") (at 73.66 64.135 0) (unit 1)
(in_bom yes) (on_board yes) (fields_autoplaced)
(uuid e38a88e5-32b2-4c8e-8e29-fd613e9fce2a)
(property "Reference" "R1" (id 0) (at 76.2 62.8649 0)
(effects (font (size 1.27 1.27)) (justify left))
)
(property "Value" "4k7" (id 1) (at 76.2 65.4049 0)
(effects (font (size 1.27 1.27)) (justify left))
)
(property "Footprint" "" (id 2) (at 71.882 64.135 90)
(effects (font (size 1.27 1.27)) hide)
)
(property "Datasheet" "~" (id 3) (at 73.66 64.135 0)
(effects (font (size 1.27 1.27)) hide)
)
(pin "1" (uuid 14717925-77d8-4e5b-87f4-d527a7df25a2))
(pin "2" (uuid 042328ba-54db-4f0f-b129-1e89e595aa37))
)
(symbol (lib_id "Device:R") (at 86.36 64.135 0) (unit 1)
(in_bom yes) (on_board yes) (fields_autoplaced)
(uuid f9457597-177c-435c-90d9-f31193f60883)
(property "Reference" "R0" (id 0) (at 88.9 62.8649 0)
(effects (font (size 1.27 1.27)) (justify left))
)
(property "Value" "8k2" (id 1) (at 88.9 65.4049 0)
(effects (font (size 1.27 1.27)) (justify left))
)
(property "Footprint" "" (id 2) (at 84.582 64.135 90)
(effects (font (size 1.27 1.27)) hide)
)
(property "Datasheet" "~" (id 3) (at 86.36 64.135 0)
(effects (font (size 1.27 1.27)) hide)
)
(pin "1" (uuid a698459c-2acc-4346-a3d9-ec53ed63917d))
(pin "2" (uuid c6c22bf2-3a43-4c40-940f-495f13d46fdd))
)
(sheet_instances
(path "/" (page "1"))
)
(symbol_instances
(path "/07a9d758-a267-455f-b30c-3770f3527e7a"
(reference "#PWR?") (unit 1) (value "GND") (footprint "")
)
(path "/a516e0a9-fe24-4120-873c-6f89d1fb49c0"
(reference "#PWR?") (unit 1) (value "+3V3") (footprint "")
)
(path "/f9457597-177c-435c-90d9-f31193f60883"
(reference "R0") (unit 1) (value "8k2") (footprint "")
)
(path "/e38a88e5-32b2-4c8e-8e29-fd613e9fce2a"
(reference "R1") (unit 1) (value "4k7") (footprint "")
)
(path "/8c50ab84-72ab-438d-a9f1-a710a33b8e06"
(reference "R2") (unit 1) (value "2k2") (footprint "")
)
(path "/769febe6-b95c-4d37-94fa-e3721ea908aa"
(reference "R3") (unit 1) (value "1k") (footprint "")
)
(path "/6eeba788-57b9-45a8-981d-ecd17efd1d54"
(reference "R_up") (unit 1) (value "1k") (footprint "")
)
(path "/3742357e-3d4f-4d99-8094-756d8329e07a"
(reference "SW0") (unit 1) (value "SW_Push") (footprint "")
)
(path "/93d3db7a-9c33-4a6b-8a4f-9c98164fe8b8"
(reference "SW1") (unit 1) (value "SW_Push") (footprint "")
)
(path "/28a1ca96-47e6-44c9-b9dc-c435e73ae941"
(reference "SW2") (unit 1) (value "SW_Push") (footprint "")
)
(path "/864b1f85-f995-433a-9a94-7965edbddf3c"
(reference "SW3") (unit 1) (value "SW_Push") (footprint "")
)
)
)

Binary file not shown.

View File

@@ -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