Compare commits
33 Commits
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
ef0ac39c9b | ||
|
|
ad2ce8c33b | ||
|
|
8f5b33c554 | ||
|
|
592351c265 | ||
|
|
d473bf6b8c | ||
|
|
4cb6b41a6b | ||
|
|
bf87be2590 | ||
|
|
63706e4aa7 | ||
|
|
5b49406cb8 | ||
|
|
2cf1762569 | ||
|
|
826dd983c4 | ||
|
|
bb7cdddc6c | ||
|
|
8a265c2bae | ||
|
|
6dfa47e3e8 | ||
|
|
2f86fbeb80 | ||
|
|
9b386c3d73 | ||
|
|
992d852189 | ||
|
|
824bad930e | ||
|
|
ced7cda002 | ||
|
|
6242d6a5fc | ||
|
|
59df1a9aa2 | ||
|
|
3a99b8bc5c | ||
|
|
451981b165 | ||
|
|
1f53fabd19 | ||
|
|
d2d85952df | ||
|
|
38ad266488 | ||
|
|
a932460924 | ||
|
|
09ee67f583 | ||
|
|
f52a58aa1c | ||
|
|
fab75661c2 | ||
|
|
9600932ae8 | ||
|
|
bb22fb340d | ||
|
|
7eb06fe228 |
1
.gitattributes
vendored
Normal file
@@ -0,0 +1 @@
|
||||
*.fcstd text
|
||||
3
.gitignore
vendored
@@ -7,3 +7,6 @@ build
|
||||
|
||||
# drawio files
|
||||
*.bkp
|
||||
|
||||
# freecad backup files
|
||||
*.FCStd1
|
||||
|
||||
BIN
cad/box/box-holder_v1.0.FCStd
Normal file
BIN
cad/box/box_v1.0.FCStd
Normal file
2356
cad/box/panel.svg
Normal file
|
After Width: | Height: | Size: 67 KiB |
BIN
cad/cable-mounts/clamps-startButtons.FCStd
Normal file
BIN
cad/cable-mounts/mounts-item.FCStd
Normal file
BIN
cad/cutter/angle-bracket_v2.0.FCStd
Normal file
BIN
cad/cutter/cutter-mount_2.2.FCStd
Normal file
BIN
cad/emergency-sw/sw_holder_v1.0.FCStd
Normal file
BIN
cad/encoder/disk-flat_SE.par
Normal file
BIN
cad/encoder/disk-flat_SE.stl
Normal file
BIN
cad/encoder/disk-half_SE.par
Normal file
BIN
cad/encoder/disk-half_SE.stl
Normal file
BIN
cad/encoder/holder_v1.0.FCStd
Normal file
BIN
cad/encoder/holder_v2.0.FCStd
Normal file
BIN
cad/encoder/holder_v3.2.FCStd
Normal file
4
cad/export/.gitignore
vendored
Normal file
@@ -0,0 +1,4 @@
|
||||
# Ignore everything in this directory
|
||||
*
|
||||
# Except this file
|
||||
!.gitignore
|
||||
BIN
cad/guides/distance-rings.FCStd
Normal file
BIN
cad/guides/guide-cutter_spacer.FCStd
Normal file
BIN
cad/guides/guide-cutter_v1.0.FCStd
Normal file
BIN
cad/guides/guide-cutter_v2.0.FCStd
Normal file
BIN
cad/guides/guide-cutter_v3.0.FCStd
Normal file
BIN
cad/guides/guide-cutter_v4.2.FCStd
Normal file
BIN
cad/guides/guide-cutter_v5.0.FCStd
Normal file
BIN
cad/guides/guide-cutter_v5.1.FCStd
Normal file
BIN
cad/guides/guide-in-long-rolls_SE.par
Normal file
BIN
cad/guides/guide-in-long-rolls_SE.stl
Normal file
BIN
cad/guides/guide-in-long_SE.par
Normal file
BIN
cad/guides/guide-in-long_SE.stl
Normal file
BIN
cad/guides/guide-in_v1.0.FCStd
Normal file
BIN
cad/guides/guide-in_v1.1.FCStd
Normal file
BIN
cad/guides/guide-in_v2.1.FCStd
Normal file
BIN
cad/reel/cable-reel_v1_SE.par
Normal file
BIN
cad/reel/cable-reel_v1_SE.stl
Normal file
BIN
cad/reel/cable-reel_v2.1.FCStd
Normal file
@@ -1,4 +1,6 @@
|
||||
idf_component_register(
|
||||
SRCS "gpio_evaluateSwitch.cpp"
|
||||
SRCS
|
||||
"gpio_evaluateSwitch.cpp"
|
||||
"gpio_adc.cpp"
|
||||
INCLUDE_DIRS "."
|
||||
)
|
||||
|
||||
21
components/gpio/gpio_adc.cpp
Normal 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;
|
||||
}
|
||||
}
|
||||
9
components/gpio/gpio_adc.hpp
Normal 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);
|
||||
@@ -9,12 +9,12 @@ gpio_evaluatedSwitch::gpio_evaluatedSwitch( //minimal (use default values)
|
||||
gpio_num = gpio_num_declare;
|
||||
pullup = true;
|
||||
inverted = false;
|
||||
inputSource = inputSource_t::GPIO;
|
||||
|
||||
init();
|
||||
initGpio();
|
||||
};
|
||||
|
||||
|
||||
|
||||
gpio_evaluatedSwitch::gpio_evaluatedSwitch( //optional parameters given
|
||||
gpio_num_t gpio_num_declare,
|
||||
bool pullup_declare,
|
||||
@@ -23,13 +23,25 @@ gpio_evaluatedSwitch::gpio_evaluatedSwitch( //optional parameters given
|
||||
gpio_num = gpio_num_declare;
|
||||
pullup = pullup_declare;
|
||||
inverted = inverted_declare;
|
||||
inputSource = inputSource_t::GPIO;
|
||||
|
||||
init();
|
||||
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::init(){
|
||||
void gpio_evaluatedSwitch::initGpio(){
|
||||
ESP_LOGI(TAG, "initializing gpio pin %d", (int)gpio_num);
|
||||
|
||||
//define gpio pin as input
|
||||
@@ -48,11 +60,33 @@ void gpio_evaluatedSwitch::init(){
|
||||
};
|
||||
|
||||
|
||||
|
||||
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 inverted switch ============
|
||||
//=================== (switch to VCC) =====================
|
||||
//========= Statemachine for evaluateing switch ===========
|
||||
//=========================================================
|
||||
switch (p_state){
|
||||
default:
|
||||
@@ -61,7 +95,7 @@ void gpio_evaluatedSwitch::handle(){ //Statemachine for debouncing and edge det
|
||||
|
||||
case switchState::FALSE: //input confirmed high (released)
|
||||
fallingEdge = false; //reset edge event
|
||||
if (gpio_get_level(gpio_num) == 1){ //pin high (on)
|
||||
if (inputState == true){ //pin high (on)
|
||||
p_state = switchState::HIGH;
|
||||
timestampHigh = esp_log_timestamp(); //save timestamp switched from low to high
|
||||
} else {
|
||||
@@ -70,7 +104,7 @@ void gpio_evaluatedSwitch::handle(){ //Statemachine for debouncing and edge det
|
||||
break;
|
||||
|
||||
case switchState::HIGH: //input recently switched to high (pressed)
|
||||
if (gpio_get_level(gpio_num) == 1){ //pin still high (on)
|
||||
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;
|
||||
@@ -84,7 +118,7 @@ void gpio_evaluatedSwitch::handle(){ //Statemachine for debouncing and edge det
|
||||
|
||||
case switchState::TRUE: //input confirmed high (pressed)
|
||||
risingEdge = false; //reset edge event
|
||||
if (gpio_get_level(gpio_num) == 0){ //pin low (off)
|
||||
if (inputState == false){ //pin low (off)
|
||||
timestampLow = esp_log_timestamp();
|
||||
p_state = switchState::LOW;
|
||||
} else {
|
||||
@@ -94,7 +128,7 @@ void gpio_evaluatedSwitch::handle(){ //Statemachine for debouncing and edge det
|
||||
break;
|
||||
|
||||
case switchState::LOW: //input recently switched to low (released)
|
||||
if (gpio_get_level(gpio_num) == 0){ //pin still low (off)
|
||||
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
|
||||
@@ -107,65 +141,6 @@ void gpio_evaluatedSwitch::handle(){ //Statemachine for debouncing and edge det
|
||||
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;
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
||||
@@ -18,21 +18,30 @@ extern "C"
|
||||
//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;
|
||||
gpio_evaluatedSwitch( //constructor minimal (default parameters pullup=true, inverted=false)
|
||||
|
||||
//constructor minimal (default parameters pullup=true, inverted=false)
|
||||
gpio_evaluatedSwitch(
|
||||
gpio_num_t gpio_num_declare
|
||||
);
|
||||
gpio_evaluatedSwitch( //constructor with optional parameters
|
||||
|
||||
//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;
|
||||
@@ -47,12 +56,15 @@ class gpio_evaluatedSwitch {
|
||||
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 init();
|
||||
void initGpio();
|
||||
|
||||
};
|
||||
|
||||
|
||||
BIN
docs/3SK1111-1AB30_con1.jpg
Normal file
|
After Width: | Height: | Size: 60 KiB |
BIN
docs/3SK1111-1AB30_con2.jpg
Normal file
|
After Width: | Height: | Size: 54 KiB |
BIN
docs/LPD3806-dimensions.jpg
Normal file
|
After Width: | Height: | Size: 31 KiB |
BIN
docs/MAX7219-MAX7221-7-segment-display.pdf
Normal file
BIN
docs/vfd/T13-400W-12-HT13-750W-12H-1.jpg
Normal file
|
After Width: | Height: | Size: 82 KiB |
BIN
docs/vfd/T13-400W-12-HT13-750W-12H-2.jpg
Normal file
|
After Width: | Height: | Size: 39 KiB |
BIN
docs/vfd/T13-400W-12-HT13-750W-12H-4.jpg
Normal file
|
After Width: | Height: | Size: 126 KiB |
BIN
docs/vfd/T13-400W-12-HT13-750W-12H.jpg
Normal file
|
After Width: | Height: | Size: 72 KiB |
2
docs/vfd/currently-used_T13-750W-12-h.txt
Normal file
@@ -0,0 +1,2 @@
|
||||
currently the vfd 'T13-750W-12-h' is actually used.
|
||||
Included documentation about T13-400W here too, modbus specification might be the same.
|
||||
BIN
docs/vfd/mcu-t13-400w-12-h.pdf
Normal file
@@ -6,6 +6,8 @@ idf_component_register(
|
||||
"buzzer.cpp"
|
||||
"vfd.cpp"
|
||||
"display.cpp"
|
||||
"cutter.cpp"
|
||||
"switchesAnalog.cpp"
|
||||
INCLUDE_DIRS
|
||||
"."
|
||||
)
|
||||
|
||||
@@ -3,13 +3,20 @@
|
||||
|
||||
//--- 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)
|
||||
//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)
|
||||
gpio_evaluatedSwitch sw_gpio_14(GPIO_NUM_14, 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);
|
||||
|
||||
@@ -4,6 +4,7 @@ extern "C" {
|
||||
}
|
||||
#include "gpio_evaluateSwitch.hpp"
|
||||
#include "buzzer.hpp"
|
||||
#include "switchesAnalog.hpp"
|
||||
|
||||
|
||||
//===================================
|
||||
@@ -16,25 +17,47 @@ extern "C" {
|
||||
#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_MOS1 GPIO_NUM_18 //mos1 (free)
|
||||
#define GPIO_LAMP GPIO_NUM_5 //mos2
|
||||
#define GPIO_RELAY GPIO_NUM_13
|
||||
#define GPIO_BUZZER GPIO_NUM_12
|
||||
|
||||
|
||||
//==================================
|
||||
//===== define input gpio pins =====
|
||||
//==== define analog input 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
|
||||
#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_CUTTER_POS sw_gpio_14
|
||||
#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
|
||||
#define SW_CUT sw_gpio_33
|
||||
#define SW_AUTO_CUT sw_gpio_32
|
||||
|
||||
//unused but already available evaluated inputs
|
||||
//#define ? sw_gpio_34
|
||||
|
||||
|
||||
|
||||
|
||||
//=============================
|
||||
//======= configuration =======
|
||||
//=============================
|
||||
//--------------------------
|
||||
//----- display config -----
|
||||
//--------------------------
|
||||
@@ -59,11 +82,20 @@ extern "C" {
|
||||
//--------------------------
|
||||
//------ calibration -------
|
||||
//--------------------------
|
||||
//use encoder test for calibration and calculate STEPS_PER_METER
|
||||
//#define ENCODER_TEST //show encoder count instead of converted meters
|
||||
//enable mode encoder test for calibration
|
||||
//if defined, displays always show length and steps instead of the normal messages
|
||||
//#define ENCODER_TEST
|
||||
|
||||
//steps per meter
|
||||
#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
|
||||
|
||||
//millimetres added to target length
|
||||
//to ensure that length does not fall short when spool slightly rotates back after stop
|
||||
#define TARGET_LENGTH_OFFSET 0
|
||||
|
||||
//millimetres lengthNow can be below lengthTarget to still stay in target_reached state
|
||||
#define TARGET_REACHED_TOLERANCE 5
|
||||
|
||||
|
||||
|
||||
|
||||
@@ -71,14 +103,22 @@ extern "C" {
|
||||
//===== 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;
|
||||
//--- 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;
|
||||
extern gpio_evaluatedSwitch sw_gpio_14;
|
||||
|
||||
//--- 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;
|
||||
|
||||
263
main/control.cpp
@@ -23,36 +23,15 @@ QueueHandle_t init_encoder(rotary_encoder_info_t * info){
|
||||
}
|
||||
|
||||
|
||||
//=============================
|
||||
//========= 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;
|
||||
const char* systemStateStr[7] = {"COUNTING", "WINDING_START", "WINDING", "TARGET_REACHED", "AUTO_CUT_WAITING", "CUTTING", "MANUAL"};
|
||||
systemState_t controlState = systemState_t::COUNTING;
|
||||
uint32_t timestamp_changedState = 0;
|
||||
|
||||
char buf_disp[20]; //both displays
|
||||
char buf_disp1[10];// 8 digits + decimal point + \0
|
||||
@@ -63,16 +42,21 @@ 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 lengthTarget = 5000; //default 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
|
||||
|
||||
//encoder test / calibration
|
||||
int lengthBeeped = 0; //only beep once per meter during encoder test
|
||||
|
||||
//automatic cut
|
||||
int cut_msRemaining = 0;
|
||||
uint32_t timestamp_cut_lastBeep = 0;
|
||||
uint32_t autoCut_delayMs = 2500; //TODO add this to config
|
||||
bool autoCutEnabled = false; //store state of toggle switch (no hotswitch)
|
||||
|
||||
|
||||
//===== change State =====
|
||||
//function for changing the controlState with log output
|
||||
@@ -85,9 +69,12 @@ void changeState (systemState_t stateNew) {
|
||||
ESP_LOGW(TAG, "changed state from %s to %s", systemStateStr[(int)controlState], systemStateStr[(int)stateNew]);
|
||||
//change state
|
||||
controlState = stateNew;
|
||||
//update timestamp
|
||||
timestamp_changedState = esp_log_timestamp();
|
||||
}
|
||||
|
||||
|
||||
|
||||
//===== 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
|
||||
@@ -96,16 +83,16 @@ bool handleStopCondition(handledDisplay * displayTop, handledDisplay * displayBo
|
||||
//stop conditions that are checked in any mode
|
||||
//target reached
|
||||
if (lengthRemaining <= 0 ) {
|
||||
changeState(TARGET_REACHED);
|
||||
changeState(systemState_t::TARGET_REACHED);
|
||||
vfd_setState(false);
|
||||
displayTop->blink(1, 0, 1500, " S0LL ");
|
||||
displayBot->blink(1, 0, 1500, "ERREICHT");
|
||||
displayTop->blink(1, 0, 1000, " S0LL ");
|
||||
displayBot->blink(1, 0, 1000, "ERREICHT");
|
||||
buzzer.beep(2, 100, 100);
|
||||
return true;
|
||||
}
|
||||
//start button released
|
||||
else if (SW_START.state == false) {
|
||||
changeState(COUNTING);
|
||||
changeState(systemState_t::COUNTING);
|
||||
vfd_setState(false);
|
||||
displayTop->blink(2, 900, 1000, "- STOP -");
|
||||
displayBot->blink(2, 900, 1000, " TASTER ");
|
||||
@@ -123,11 +110,11 @@ bool handleStopCondition(handledDisplay * displayTop, handledDisplay * displayBo
|
||||
void setDynSpeedLvl(uint8_t lvlMax = 3){
|
||||
uint8_t lvl;
|
||||
//define speed level according to difference
|
||||
if (lengthRemaining < 50) {
|
||||
if (lengthRemaining < 40) {
|
||||
lvl = 0;
|
||||
} else if (lengthRemaining < 200) {
|
||||
} else if (lengthRemaining < 300) {
|
||||
lvl = 1;
|
||||
} else if (lengthRemaining < 600) {
|
||||
} else if (lengthRemaining < 700) {
|
||||
lvl = 2;
|
||||
} else { //more than last step remaining
|
||||
lvl = 3;
|
||||
@@ -167,7 +154,7 @@ void task_control(void *pvParameter)
|
||||
//===== loop =====
|
||||
//================
|
||||
while(1){
|
||||
vTaskDelay(20 / portTICK_PERIOD_MS);
|
||||
vTaskDelay(10 / portTICK_PERIOD_MS);
|
||||
|
||||
//-----------------------------
|
||||
//------ handle switches ------
|
||||
@@ -179,8 +166,15 @@ void task_control(void *pvParameter)
|
||||
SW_PRESET1.handle();
|
||||
SW_PRESET2.handle();
|
||||
SW_PRESET3.handle();
|
||||
SW_CUT.handle();
|
||||
SW_AUTO_CUT.handle();
|
||||
|
||||
|
||||
//---------------------------
|
||||
//------ handle cutter ------
|
||||
//---------------------------
|
||||
cutter_handle();
|
||||
|
||||
|
||||
//----------------------------
|
||||
//------ rotary encoder ------
|
||||
@@ -188,39 +182,82 @@ void task_control(void *pvParameter)
|
||||
// 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) {
|
||||
//dont reset when press used for stopping pending auto-cut
|
||||
if (controlState != systemState_t::AUTO_CUT_WAITING) {
|
||||
rotary_encoder_reset(&encoder);
|
||||
lengthNow = 0;
|
||||
buzzer.beep(1, 700, 100);
|
||||
displayTop.blink(2, 100, 100, "1ST ");
|
||||
//TODO: stop cutter with reset switch?
|
||||
//cutter_stop();
|
||||
}
|
||||
}
|
||||
|
||||
//--- CUT switch ---
|
||||
//start cut cycle immediately
|
||||
if (SW_CUT.risingEdge) {
|
||||
//stop cutter if already running
|
||||
if (cutter_isRunning()) {
|
||||
cutter_stop();
|
||||
buzzer.beep(1, 600, 0);
|
||||
}
|
||||
else if (controlState == systemState_t::AUTO_CUT_WAITING) {
|
||||
//do nothing when press used for stopping pending auto-cut
|
||||
}
|
||||
//start cutter when motor not active
|
||||
else if (controlState != systemState_t::WINDING_START //TODO use vfd state here?
|
||||
&& controlState != systemState_t::WINDING) {
|
||||
cutter_start();
|
||||
buzzer.beep(1, 70, 50);
|
||||
}
|
||||
//error cant cut while motor is on
|
||||
else {
|
||||
buzzer.beep(6, 100, 50);
|
||||
}
|
||||
}
|
||||
|
||||
//--- AUTO_CUT toggle sw ---
|
||||
//beep at change
|
||||
if (SW_AUTO_CUT.risingEdge) {
|
||||
buzzer.beep(2, 100, 50);
|
||||
} else if (SW_AUTO_CUT.fallingEdge) {
|
||||
buzzer.beep(1, 400, 50);
|
||||
}
|
||||
//update enabled state
|
||||
if (SW_AUTO_CUT.state) {
|
||||
//enable autocut when not in target_reached state
|
||||
//(prevent immediate/unexpected cut)
|
||||
if (controlState != systemState_t::TARGET_REACHED) {
|
||||
autoCutEnabled = true;
|
||||
}
|
||||
} else {
|
||||
//disable anytime (also stops countdown to auto cut)
|
||||
autoCutEnabled = false;
|
||||
}
|
||||
|
||||
//--- manual mode ---
|
||||
//switch to manual motor control (2 buttons + poti)
|
||||
if ( SW_PRESET2.state && (SW_PRESET1.state || SW_PRESET3.state) && controlState != MANUAL ) {
|
||||
if ( SW_PRESET2.state && (SW_PRESET1.state || SW_PRESET3.state) && controlState != systemState_t::MANUAL ) {
|
||||
//enable manual control
|
||||
changeState(MANUAL);
|
||||
changeState(systemState_t::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
|
||||
potiRead = gpio_readAdc(ADC_CHANNEL_POTI); //0-4095
|
||||
//scale to target length range
|
||||
int lengthTargetNew = (float)potiRead / 4095 * 30000;
|
||||
int lengthTargetNew = (float)potiRead / 4095 * 50000;
|
||||
//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);
|
||||
@@ -251,22 +288,22 @@ void task_control(void *pvParameter)
|
||||
|
||||
|
||||
//--- target length presets ---
|
||||
if (controlState != MANUAL) { //dont apply preset length while controlling motor with preset buttons
|
||||
if (controlState != systemState_t::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) {
|
||||
else if (SW_PRESET2.risingEdge) {
|
||||
lengthTarget = 10000;
|
||||
buzzer.beep(lengthTarget/1000, 25, 30);
|
||||
displayBot.blink(2, 100, 100, "S0LL ");
|
||||
}
|
||||
else if (SW_PRESET3.risingEdge) {
|
||||
lengthTarget = 15000;
|
||||
buzzer.beep(lengthTarget/1000, 25, 30);
|
||||
displayBot.blink(2, 100, 100, "S0LL ");
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -275,17 +312,16 @@ void task_control(void *pvParameter)
|
||||
//--------- control ---------
|
||||
//---------------------------
|
||||
//calculate length difference
|
||||
lengthRemaining = lengthTarget - lengthNow;
|
||||
lengthRemaining = lengthTarget - lengthNow + TARGET_LENGTH_OFFSET;
|
||||
|
||||
//--- statemachine ---
|
||||
switch (controlState) {
|
||||
case COUNTING: //no motor action
|
||||
case systemState_t::COUNTING: //no motor action
|
||||
vfd_setState(false);
|
||||
//TODO check stop condition before starting - prevents motor from starting 2 cycles when
|
||||
//TODO check stop condition before starting - prevents motor from starting 2 cycles when already at target
|
||||
//--- start winding to length ---
|
||||
if (SW_START.risingEdge) {
|
||||
changeState(WINDING_START);
|
||||
//TODO apply dynamic speed here too (if started when already very close)
|
||||
changeState(systemState_t::WINDING_START);
|
||||
vfd_setSpeedLevel(1); //start at low speed
|
||||
vfd_setState(true); //start motor
|
||||
timestamp_motorStarted = esp_log_timestamp(); //save time started
|
||||
@@ -293,57 +329,100 @@ void task_control(void *pvParameter)
|
||||
}
|
||||
break;
|
||||
|
||||
case WINDING_START: //wind slow for certain time
|
||||
case systemState_t::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);
|
||||
if (esp_log_timestamp() - timestamp_motorStarted > 3000) {
|
||||
changeState(systemState_t::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
|
||||
case systemState_t::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:
|
||||
case systemState_t::TARGET_REACHED:
|
||||
vfd_setState(false);
|
||||
//switch to counting state when no longer at or above target length
|
||||
if ( lengthRemaining > 0 ) {
|
||||
changeState(COUNTING);
|
||||
if ( lengthNow < lengthTarget - TARGET_REACHED_TOLERANCE ) {
|
||||
changeState(systemState_t::COUNTING);
|
||||
}
|
||||
//switch initiate countdown to auto-cut
|
||||
else if ( (autoCutEnabled)
|
||||
&& (esp_log_timestamp() - timestamp_changedState > 300) ) { //wait for dislay msg "reached" to finish
|
||||
changeState(systemState_t::AUTO_CUT_WAITING);
|
||||
}
|
||||
//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");
|
||||
buzzer.beep(2, 50, 30);
|
||||
displayTop.blink(2, 600, 500, " S0LL ");
|
||||
displayBot.blink(2, 600, 500, "ERREICHT");
|
||||
}
|
||||
break;
|
||||
|
||||
case MANUAL: //manually control motor via preset buttons + poti
|
||||
case systemState_t::AUTO_CUT_WAITING:
|
||||
//handle delayed start of cut
|
||||
cut_msRemaining = autoCut_delayMs - (esp_log_timestamp() - timestamp_changedState);
|
||||
//- countdown stop conditions -
|
||||
//stop with any button
|
||||
if (!autoCutEnabled
|
||||
|| SW_RESET.state || SW_CUT.state
|
||||
|| SW_SET.state || SW_PRESET1.state
|
||||
|| SW_PRESET2.state || SW_PRESET3.state) {//TODO: also stop when target not reached anymore?
|
||||
changeState(systemState_t::COUNTING);
|
||||
buzzer.beep(5, 100, 50);
|
||||
}
|
||||
//- trigger cut if delay passed -
|
||||
else if (cut_msRemaining <= 0) {
|
||||
cutter_start();
|
||||
changeState(systemState_t::CUTTING);
|
||||
}
|
||||
//- beep countdown -
|
||||
//time passed since last beep > time remaining / 6
|
||||
else if ( (esp_log_timestamp() - timestamp_cut_lastBeep) > (cut_msRemaining / 6)
|
||||
&& (esp_log_timestamp() - timestamp_cut_lastBeep) > 50 ) { //dont trigger beeps faster than beep time
|
||||
buzzer.beep(1, 50, 0);
|
||||
timestamp_cut_lastBeep = esp_log_timestamp();
|
||||
}
|
||||
break;
|
||||
|
||||
case systemState_t::CUTTING:
|
||||
//exit when finished cutting
|
||||
if (cutter_isRunning() == false) {
|
||||
//TODO stop if start buttons released?
|
||||
changeState(systemState_t::COUNTING);
|
||||
//TODO reset automatically or wait for manual reset?
|
||||
rotary_encoder_reset(&encoder);
|
||||
lengthNow = 0;
|
||||
buzzer.beep(1, 700, 100);
|
||||
}
|
||||
break;
|
||||
|
||||
case systemState_t::MANUAL: //manually control motor via preset buttons + poti
|
||||
//read poti value
|
||||
potiRead = readAdc(ADC_CHANNEL_POTI); //0-4095
|
||||
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);
|
||||
changeState(systemState_t::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_setSpeedLevel(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_setSpeedLevel(level);
|
||||
vfd_setState(true, FWD);
|
||||
sprintf(buf_disp2, " %02i--]", level);
|
||||
}
|
||||
@@ -385,12 +464,18 @@ void task_control(void *pvParameter)
|
||||
//--------------------------
|
||||
//run handle function
|
||||
displayTop.handle();
|
||||
//show current position on display
|
||||
//indicate upcoming cut when pending
|
||||
if (controlState == systemState_t::AUTO_CUT_WAITING) {
|
||||
displayTop.blinkStrings(" CUT 1N ", " ", 70, 30);
|
||||
}
|
||||
//otherwise show current position
|
||||
else {
|
||||
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);
|
||||
}
|
||||
|
||||
|
||||
//--------------------------
|
||||
@@ -404,8 +489,18 @@ void task_control(void *pvParameter)
|
||||
displayBot.blinkStrings(buf_tmp, "S0LL ", 300, 100);
|
||||
}
|
||||
//manual state: blink "manual"
|
||||
else if (controlState == MANUAL) {
|
||||
displayBot.blinkStrings(" MANUAL ", buf_disp2, 1000, 1000);
|
||||
else if (controlState == systemState_t::MANUAL) {
|
||||
displayBot.blinkStrings(" MANUAL ", buf_disp2, 400, 800);
|
||||
}
|
||||
//notify that cutter is active
|
||||
else if (cutter_isRunning()) {
|
||||
displayBot.blinkStrings("CUTTING]", "CUTTING[", 100, 100);
|
||||
}
|
||||
//show ms countdown to cut when pending
|
||||
else if (controlState == systemState_t::AUTO_CUT_WAITING) {
|
||||
sprintf(buf_disp2, " %04d ", cut_msRemaining);
|
||||
//displayBot.showString(buf_disp2); //TODO:blink "erreicht" overrides this. for now using blink as workaround
|
||||
displayBot.blinkStrings(buf_disp2, buf_disp2, 100, 100);
|
||||
}
|
||||
//otherwise show target length
|
||||
else {
|
||||
@@ -416,13 +511,25 @@ void task_control(void *pvParameter)
|
||||
}
|
||||
|
||||
|
||||
//----------------------------
|
||||
//------- control lamp -------
|
||||
//----------------------------
|
||||
//basic functionality of lamp:
|
||||
//turn on when not idling
|
||||
//TODO: add switch-case for different sates
|
||||
//e.g. blink with different frequencies in different states
|
||||
if (controlState != systemState_t::COUNTING
|
||||
&& controlState != systemState_t::TARGET_REACHED) {
|
||||
gpio_set_level(GPIO_LAMP, 1);
|
||||
}
|
||||
else {
|
||||
gpio_set_level(GPIO_LAMP, 0);
|
||||
}
|
||||
|
||||
|
||||
|
||||
#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
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
@@ -18,14 +18,18 @@ extern "C"
|
||||
|
||||
#include "config.hpp"
|
||||
#include "gpio_evaluateSwitch.hpp"
|
||||
#include "gpio_adc.hpp"
|
||||
#include "buzzer.hpp"
|
||||
#include "vfd.hpp"
|
||||
#include "display.hpp"
|
||||
#include "cutter.hpp"
|
||||
|
||||
|
||||
|
||||
typedef enum systemState_t {COUNTING, WINDING_START, WINDING, TARGET_REACHED, MANUAL} systemState_t;
|
||||
extern const char* systemStateStr[5];
|
||||
|
||||
//enum describing the state of the system
|
||||
enum class systemState_t {COUNTING, WINDING_START, WINDING, TARGET_REACHED, AUTO_CUT_WAITING, CUTTING, MANUAL};
|
||||
//array with enum as strings for logging states
|
||||
extern const char* systemStateStr[7];
|
||||
|
||||
//task that controls the entire machine (has to be created as task in main function)
|
||||
void task_control(void *pvParameter);
|
||||
|
||||
169
main/cutter.cpp
Normal file
@@ -0,0 +1,169 @@
|
||||
#include "cutter.hpp"
|
||||
|
||||
const char* cutter_stateStr[5] = {"IDLE", "START", "CUTTING", "CANCELED", "TIMEOUT"}; //define strings for logging the state
|
||||
|
||||
|
||||
//---------------------------
|
||||
//----- local functions -----
|
||||
//---------------------------
|
||||
//declare local functions
|
||||
void setState(cutter_state_t stateNew);
|
||||
bool checkTimeout();
|
||||
|
||||
|
||||
|
||||
//---------------------------
|
||||
//----- local variables -----
|
||||
//---------------------------
|
||||
cutter_state_t cutter_state = cutter_state_t::IDLE;
|
||||
uint32_t timestamp_turnedOn;
|
||||
uint32_t msTimeout = 3000;
|
||||
static const char *TAG = "cutter"; //tag for logging
|
||||
|
||||
|
||||
|
||||
//=========================
|
||||
//========= start =========
|
||||
//=========================
|
||||
void cutter_start(){
|
||||
setState(cutter_state_t::START);
|
||||
//starts motor on state change
|
||||
}
|
||||
|
||||
|
||||
|
||||
//========================
|
||||
//========= stop =========
|
||||
//========================
|
||||
void cutter_stop(){
|
||||
if(cutter_state != cutter_state_t::IDLE){
|
||||
setState(cutter_state_t::CANCELED);
|
||||
}
|
||||
//starts motor on state change
|
||||
}
|
||||
|
||||
|
||||
|
||||
//===========================
|
||||
//===== cutter_getState =====
|
||||
//===========================
|
||||
cutter_state_t cutter_getState(){
|
||||
return cutter_state;
|
||||
}
|
||||
|
||||
|
||||
|
||||
//============================
|
||||
//===== cutter_isRunning =====
|
||||
//============================
|
||||
bool cutter_isRunning(){
|
||||
if (cutter_state == cutter_state_t::START
|
||||
|| cutter_state == cutter_state_t::CUTTING) {
|
||||
return true;
|
||||
} else {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
//---------------------------
|
||||
//-------- setState ---------
|
||||
//---------------------------
|
||||
//local function for changing state, taking corresponding actions and sending log output
|
||||
void setState(cutter_state_t stateNew){
|
||||
//only proceed and send log output when state or direction actually changed
|
||||
if ( cutter_state == stateNew) {
|
||||
//already at target state -> do nothing
|
||||
return;
|
||||
}
|
||||
|
||||
//log old and new state
|
||||
ESP_LOGI(TAG, "CHANGING state from: %s",cutter_stateStr[(int)cutter_state]);
|
||||
ESP_LOGI(TAG, "CHANGING state to: %s",cutter_stateStr[(int)stateNew]);
|
||||
//update stored state
|
||||
cutter_state = stateNew;
|
||||
|
||||
switch(stateNew){
|
||||
case cutter_state_t::IDLE:
|
||||
case cutter_state_t::TIMEOUT:
|
||||
case cutter_state_t::CANCELED:
|
||||
//--- turn motor off ---
|
||||
gpio_set_level(GPIO_RELAY, 0);
|
||||
break;
|
||||
|
||||
case cutter_state_t::START:
|
||||
case cutter_state_t::CUTTING:
|
||||
//--- turn motor on ---
|
||||
gpio_set_level(GPIO_RELAY, 1);
|
||||
//update state, timestamp
|
||||
timestamp_turnedOn = esp_log_timestamp();
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
//--------------------------
|
||||
//------ checkTimeout ------
|
||||
//--------------------------
|
||||
//local function that checks for timeout
|
||||
bool checkTimeout(){
|
||||
if (esp_log_timestamp() - timestamp_turnedOn > msTimeout){
|
||||
setState(cutter_state_t::TIMEOUT);
|
||||
return true;
|
||||
} else {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
//========================
|
||||
//======== handle ========
|
||||
//========================
|
||||
//function that handles the cutter logic -> has to be run repeatedly
|
||||
void cutter_handle(){
|
||||
//handle evaluated switch (position switch)
|
||||
SW_CUTTER_POS.handle();
|
||||
//TODO add custom thresholds once at initialization?
|
||||
//SW_CUTTER_POS.minOnMs = 10;
|
||||
//SW_CUTTER_POS.minOffMs = 10;
|
||||
|
||||
|
||||
switch(cutter_state){
|
||||
case cutter_state_t::IDLE:
|
||||
case cutter_state_t::TIMEOUT:
|
||||
case cutter_state_t::CANCELED:
|
||||
//wait for state change via cutter_start();
|
||||
break;
|
||||
|
||||
case cutter_state_t::START:
|
||||
//--- moved away from idle position ---
|
||||
//if (gpio_get_level(GPIO_CUTTER_POS_SW) == 0){ //contact closed
|
||||
if (SW_CUTTER_POS.state == true) { //contact closed -> not at idle pos
|
||||
setState(cutter_state_t::CUTTING);
|
||||
}
|
||||
//--- timeout ---
|
||||
else {
|
||||
checkTimeout();
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case cutter_state_t::CUTTING:
|
||||
//--- idle position reached ---
|
||||
//if (gpio_get_level(GPIO_CUTTER_POS_SW) == 1){ //contact not closed
|
||||
//TODO: add min on duration
|
||||
if (SW_CUTTER_POS.state == false) { //contact open -> at idle pos
|
||||
setState(cutter_state_t::IDLE);
|
||||
}
|
||||
//--- timeout ---
|
||||
else {
|
||||
checkTimeout();
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
37
main/cutter.hpp
Normal file
@@ -0,0 +1,37 @@
|
||||
#pragma once
|
||||
|
||||
extern "C"
|
||||
{
|
||||
#include <stdio.h>
|
||||
#include "esp_log.h"
|
||||
}
|
||||
|
||||
#include "buzzer.hpp"
|
||||
#include "display.hpp"
|
||||
#include "gpio_evaluateSwitch.hpp"
|
||||
|
||||
|
||||
//--- variables ---
|
||||
//enum for state of cutter
|
||||
enum class cutter_state_t {IDLE, START, CUTTING, CANCELED, TIMEOUT};
|
||||
//string for logging the state name
|
||||
extern const char* cutter_stateStr[5];
|
||||
|
||||
|
||||
|
||||
//--- functions ---
|
||||
//trigger cut cycle (no effect if already running)
|
||||
void cutter_start();
|
||||
|
||||
//cancel cutting action
|
||||
void cutter_stop();
|
||||
|
||||
//return current state
|
||||
cutter_state_t cutter_getState();
|
||||
//TODO: bool cutter_isOn() (simply return boolean instead of enum)
|
||||
|
||||
//check if cutter is currently operating
|
||||
bool cutter_isRunning();
|
||||
|
||||
//handle function - has to be run repeatedly
|
||||
void cutter_handle();
|
||||
@@ -34,7 +34,7 @@ max7219_t display_init(){
|
||||
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));
|
||||
ESP_ERROR_CHECK(max7219_set_brightness(&dev, 8)); //TODO add this to config
|
||||
return dev;
|
||||
//display = dev;
|
||||
ESP_LOGI(TAG, "initializing display - done");
|
||||
@@ -50,7 +50,7 @@ void display_ShowWelcomeMsg(max7219_t dev){
|
||||
//show name and date
|
||||
ESP_LOGI(TAG, "showing startup message...");
|
||||
max7219_clear(&dev);
|
||||
max7219_draw_text_7seg(&dev, 0, "CUTTER 20.08.2022");
|
||||
max7219_draw_text_7seg(&dev, 0, "CUTTER 29.09.2022");
|
||||
// 1234567812 34 5678
|
||||
vTaskDelay(pdMS_TO_TICKS(700));
|
||||
//scroll "hello" over 2 displays
|
||||
@@ -60,6 +60,11 @@ void display_ShowWelcomeMsg(max7219_t dev){
|
||||
max7219_draw_text_7seg(&dev, 0, hello + (22 - offset) );
|
||||
vTaskDelay(pdMS_TO_TICKS(50));
|
||||
}
|
||||
|
||||
//noticed rare bug that one display does not initialize / is not configured correctly after start
|
||||
//initialize display again after the welcome message in case it did not work the first time
|
||||
ESP_ERROR_CHECK(max7219_init(&dev));
|
||||
ESP_ERROR_CHECK(max7219_set_brightness(&dev, 8)); //TODO add this to config
|
||||
}
|
||||
|
||||
|
||||
|
||||
@@ -13,37 +13,42 @@ extern "C"
|
||||
#include "config.hpp"
|
||||
#include "control.hpp"
|
||||
#include "buzzer.hpp"
|
||||
#include "switchesAnalog.hpp"
|
||||
|
||||
|
||||
//=================================
|
||||
//=========== functions ===========
|
||||
//=================================
|
||||
//--- configure output ---
|
||||
//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);
|
||||
}
|
||||
|
||||
|
||||
//--- init gpios ---
|
||||
void init_gpios(){
|
||||
//initialize all outputs
|
||||
//--- 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_REV);
|
||||
//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);
|
||||
gpio_configure_output(GPIO_MOS1); //mos1
|
||||
gpio_configure_output(GPIO_LAMP); //llamp (mos2)
|
||||
//onboard relay and buzzer
|
||||
gpio_configure_output(GPIO_RELAY);
|
||||
gpio_configure_output(GPIO_BUZZER);
|
||||
//5v regulator
|
||||
gpio_configure_output(GPIO_NUM_17);
|
||||
|
||||
//--- inputs ---
|
||||
//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
|
||||
|
||||
}
|
||||
|
||||
|
||||
@@ -51,8 +56,6 @@ void init_gpios(){
|
||||
//======================================
|
||||
//============ 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
|
||||
@@ -62,8 +65,6 @@ void task_buzzer( void * pvParameters ){
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
//======================================
|
||||
//=========== main function ============
|
||||
//======================================
|
||||
@@ -78,6 +79,7 @@ extern "C" void app_main()
|
||||
//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
|
||||
|
||||
103
main/switchesAnalog.cpp
Normal 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
@@ -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();
|
||||
@@ -38,11 +38,9 @@ void vfd_setState(bool stateNew, vfd_direction_t directionNew){
|
||||
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);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
75
pcb/4swToAdc.kicad_prl
Normal 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
@@ -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
@@ -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 "")
|
||||
)
|
||||
)
|
||||
)
|
||||