├── .gitignore ├── CMakeLists.txt ├── Install.md ├── LICENSE ├── README.md ├── TODO.md ├── config.ini.template.ini ├── include └── README ├── lib └── .foo ├── nativeStatic.py ├── platformio.ini ├── sdkconfig ├── src ├── CMakeLists.txt ├── main.cpp └── src │ ├── BounceMode.cpp │ ├── BounceMode.h │ ├── Controls.cpp │ ├── Controls.h │ ├── DebugMode.cpp │ ├── DebugMode.h │ ├── Encoder.cpp │ ├── Encoder.h │ ├── Machine.cpp │ ├── Machine.h │ ├── SlaveMode.cpp │ ├── SlaveMode.h │ ├── Stepper.cpp │ ├── Stepper.h │ ├── config.h │ ├── display.cpp │ ├── display.h │ ├── gear.h │ ├── genStepper.h │ ├── hob.cpp │ ├── hob.h │ ├── led.cpp │ ├── led.h │ ├── log.cpp │ ├── log.h │ ├── mocks.h │ ├── motion.cpp │ ├── motion.h │ ├── moveConfig.h │ ├── myperfmon.c │ ├── myperfmon.h │ ├── neotimer.cpp │ ├── neotimer.h │ ├── pcntEncoder.cpp │ ├── pcntEncoder.h │ ├── rmtStepper.h │ ├── state.cpp │ ├── state.h │ ├── util.cpp │ ├── util.h │ ├── web.cpp │ └── web.h └── test ├── README ├── test_desktop └── test_gear.cpp ├── test_pos └── test_pos.cpp ├── test_speed └── test_speed.cpp └── test_stepper └── test_stepper.cpp /.gitignore: -------------------------------------------------------------------------------- 1 | .pio 2 | .vscode/.browse.c_cpp.db* 3 | .vscode/c_cpp_properties.json 4 | .vscode/launch.json 5 | .vscode/ipch 6 | .vscode/extensions.json 7 | 8 | build/ 9 | wifisecret.h 10 | config.ini -------------------------------------------------------------------------------- /CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.16.0) 2 | include($ENV{IDF_PATH}/tools/cmake/project.cmake) 3 | project(ESPels) 4 | -------------------------------------------------------------------------------- /Install.md: -------------------------------------------------------------------------------- 1 | # Install instructions 2 | 3 | ## Starter Bench Install 4 | 5 | The only thing you really need to get this tested is an esp32. You can simulate the encoder and play with the code without hooking anything up. 6 | 7 | Here's a quick demo: TODO: demo 8 | 9 | If you want to get frisky you can hook up the pulse pin to a scope and watch them fire away!!! 10 | 11 | ## Step 1 12 | 13 | Install and configure PlatformIO and install the packages for esp32 arduino 14 | git clone this repo 15 | open the ESPels folder in platformIO 16 | 17 | ## Step 2 18 | 19 | copy the config.ini.template.ini file in the base directory to config.ini 20 | edit the config with your settings. 21 | 22 | ## step 3 23 | 24 | Build and flash 25 | 26 | 27 | ## Full config and board 28 | 29 | external pullups, board, led, buttons, screens etc etc 30 | -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | Apache License 2 | Version 2.0, January 2004 3 | http://www.apache.org/licenses/ 4 | 5 | TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION 6 | 7 | 1. Definitions. 8 | 9 | "License" shall mean the terms and conditions for use, reproduction, 10 | and distribution as defined by Sections 1 through 9 of this document. 11 | 12 | "Licensor" shall mean the copyright owner or entity authorized by 13 | the copyright owner that is granting the License. 14 | 15 | "Legal Entity" shall mean the union of the acting entity and all 16 | other entities that control, are controlled by, or are under common 17 | control with that entity. For the purposes of this definition, 18 | "control" means (i) the power, direct or indirect, to cause the 19 | direction or management of such entity, whether by contract or 20 | otherwise, or (ii) ownership of fifty percent (50%) or more of the 21 | outstanding shares, or (iii) beneficial ownership of such entity. 22 | 23 | "You" (or "Your") shall mean an individual or Legal Entity 24 | exercising permissions granted by this License. 25 | 26 | "Source" form shall mean the preferred form for making modifications, 27 | including but not limited to software source code, documentation 28 | source, and configuration files. 29 | 30 | "Object" form shall mean any form resulting from mechanical 31 | transformation or translation of a Source form, including but 32 | not limited to compiled object code, generated documentation, 33 | and conversions to other media types. 34 | 35 | "Work" shall mean the work of authorship, whether in Source or 36 | Object form, made available under the License, as indicated by a 37 | copyright notice that is included in or attached to the work 38 | (an example is provided in the Appendix below). 39 | 40 | "Derivative Works" shall mean any work, whether in Source or Object 41 | form, that is based on (or derived from) the Work and for which the 42 | editorial revisions, annotations, elaborations, or other modifications 43 | represent, as a whole, an original work of authorship. For the purposes 44 | of this License, Derivative Works shall not include works that remain 45 | separable from, or merely link (or bind by name) to the interfaces of, 46 | the Work and Derivative Works thereof. 47 | 48 | "Contribution" shall mean any work of authorship, including 49 | the original version of the Work and any modifications or additions 50 | to that Work or Derivative Works thereof, that is intentionally 51 | submitted to Licensor for inclusion in the Work by the copyright owner 52 | or by an individual or Legal Entity authorized to submit on behalf of 53 | the copyright owner. For the purposes of this definition, "submitted" 54 | means any form of electronic, verbal, or written communication sent 55 | to the Licensor or its representatives, including but not limited to 56 | communication on electronic mailing lists, source code control systems, 57 | and issue tracking systems that are managed by, or on behalf of, the 58 | Licensor for the purpose of discussing and improving the Work, but 59 | excluding communication that is conspicuously marked or otherwise 60 | designated in writing by the copyright owner as "Not a Contribution." 61 | 62 | "Contributor" shall mean Licensor and any individual or Legal Entity 63 | on behalf of whom a Contribution has been received by Licensor and 64 | subsequently incorporated within the Work. 65 | 66 | 2. Grant of Copyright License. Subject to the terms and conditions of 67 | this License, each Contributor hereby grants to You a perpetual, 68 | worldwide, non-exclusive, no-charge, royalty-free, irrevocable 69 | copyright license to reproduce, prepare Derivative Works of, 70 | publicly display, publicly perform, sublicense, and distribute the 71 | Work and such Derivative Works in Source or Object form. 72 | 73 | 3. Grant of Patent License. Subject to the terms and conditions of 74 | this License, each Contributor hereby grants to You a perpetual, 75 | worldwide, non-exclusive, no-charge, royalty-free, irrevocable 76 | (except as stated in this section) patent license to make, have made, 77 | use, offer to sell, sell, import, and otherwise transfer the Work, 78 | where such license applies only to those patent claims licensable 79 | by such Contributor that are necessarily infringed by their 80 | Contribution(s) alone or by combination of their Contribution(s) 81 | with the Work to which such Contribution(s) was submitted. If You 82 | institute patent litigation against any entity (including a 83 | cross-claim or counterclaim in a lawsuit) alleging that the Work 84 | or a Contribution incorporated within the Work constitutes direct 85 | or contributory patent infringement, then any patent licenses 86 | granted to You under this License for that Work shall terminate 87 | as of the date such litigation is filed. 88 | 89 | 4. Redistribution. You may reproduce and distribute copies of the 90 | Work or Derivative Works thereof in any medium, with or without 91 | modifications, and in Source or Object form, provided that You 92 | meet the following conditions: 93 | 94 | (a) You must give any other recipients of the Work or 95 | Derivative Works a copy of this License; and 96 | 97 | (b) You must cause any modified files to carry prominent notices 98 | stating that You changed the files; and 99 | 100 | (c) You must retain, in the Source form of any Derivative Works 101 | that You distribute, all copyright, patent, trademark, and 102 | attribution notices from the Source form of the Work, 103 | excluding those notices that do not pertain to any part of 104 | the Derivative Works; and 105 | 106 | (d) If the Work includes a "NOTICE" text file as part of its 107 | distribution, then any Derivative Works that You distribute must 108 | include a readable copy of the attribution notices contained 109 | within such NOTICE file, excluding those notices that do not 110 | pertain to any part of the Derivative Works, in at least one 111 | of the following places: within a NOTICE text file distributed 112 | as part of the Derivative Works; within the Source form or 113 | documentation, if provided along with the Derivative Works; or, 114 | within a display generated by the Derivative Works, if and 115 | wherever such third-party notices normally appear. The contents 116 | of the NOTICE file are for informational purposes only and 117 | do not modify the License. You may add Your own attribution 118 | notices within Derivative Works that You distribute, alongside 119 | or as an addendum to the NOTICE text from the Work, provided 120 | that such additional attribution notices cannot be construed 121 | as modifying the License. 122 | 123 | You may add Your own copyright statement to Your modifications and 124 | may provide additional or different license terms and conditions 125 | for use, reproduction, or distribution of Your modifications, or 126 | for any such Derivative Works as a whole, provided Your use, 127 | reproduction, and distribution of the Work otherwise complies with 128 | the conditions stated in this License. 129 | 130 | 5. Submission of Contributions. Unless You explicitly state otherwise, 131 | any Contribution intentionally submitted for inclusion in the Work 132 | by You to the Licensor shall be under the terms and conditions of 133 | this License, without any additional terms or conditions. 134 | Notwithstanding the above, nothing herein shall supersede or modify 135 | the terms of any separate license agreement you may have executed 136 | with Licensor regarding such Contributions. 137 | 138 | 6. Trademarks. This License does not grant permission to use the trade 139 | names, trademarks, service marks, or product names of the Licensor, 140 | except as required for reasonable and customary use in describing the 141 | origin of the Work and reproducing the content of the NOTICE file. 142 | 143 | 7. Disclaimer of Warranty. Unless required by applicable law or 144 | agreed to in writing, Licensor provides the Work (and each 145 | Contributor provides its Contributions) on an "AS IS" BASIS, 146 | WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or 147 | implied, including, without limitation, any warranties or conditions 148 | of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A 149 | PARTICULAR PURPOSE. You are solely responsible for determining the 150 | appropriateness of using or redistributing the Work and assume any 151 | risks associated with Your exercise of permissions under this License. 152 | 153 | 8. Limitation of Liability. In no event and under no legal theory, 154 | whether in tort (including negligence), contract, or otherwise, 155 | unless required by applicable law (such as deliberate and grossly 156 | negligent acts) or agreed to in writing, shall any Contributor be 157 | liable to You for damages, including any direct, indirect, special, 158 | incidental, or consequential damages of any character arising as a 159 | result of this License or out of the use or inability to use the 160 | Work (including but not limited to damages for loss of goodwill, 161 | work stoppage, computer failure or malfunction, or any and all 162 | other commercial damages or losses), even if such Contributor 163 | has been advised of the possibility of such damages. 164 | 165 | 9. Accepting Warranty or Additional Liability. While redistributing 166 | the Work or Derivative Works thereof, You may choose to offer, 167 | and charge a fee for, acceptance of support, warranty, indemnity, 168 | or other liability obligations and/or rights consistent with this 169 | License. However, in accepting such obligations, You may act only 170 | on Your own behalf and on Your sole responsibility, not on behalf 171 | of any other Contributor, and only if You agree to indemnify, 172 | defend, and hold each Contributor harmless for any liability 173 | incurred by, or claims asserted against, such Contributor by reason 174 | of your accepting any such warranty or additional liability. 175 | 176 | END OF TERMS AND CONDITIONS 177 | 178 | APPENDIX: How to apply the Apache License to your work. 179 | 180 | To apply the Apache License to your work, attach the following 181 | boilerplate notice, with the fields enclosed by brackets "[]" 182 | replaced with your own identifying information. (Don't include 183 | the brackets!) The text should be enclosed in the appropriate 184 | comment syntax for the file format. We also recommend that a 185 | file or class name and description of purpose be included on the 186 | same "printed page" as the copyright notice for easier 187 | identification within third-party archives. 188 | 189 | Copyright [yyyy] [name of copyright owner] 190 | 191 | Licensed under the Apache License, Version 2.0 (the "License"); 192 | you may not use this file except in compliance with the License. 193 | You may obtain a copy of the License at 194 | 195 | http://www.apache.org/licenses/LICENSE-2.0 196 | 197 | Unless required by applicable law or agreed to in writing, software 198 | distributed under the License is distributed on an "AS IS" BASIS, 199 | WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 200 | See the License for the specific language governing permissions and 201 | limitations under the License. 202 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | ## ESPels: A simple electronic lead screw for the esp32. 2 | 3 | Join us on discord: https://discord.gg/Z2CqK4Kk 4 | 5 | 6 | 7 | __DANGER__ 8 | There is no estop right now, not safe. Use at your own risk and hover over the lathe e-stop. The thing could go crazy and crash the carriage into the spindle at any moment. It shouldn't but bugs happen.... 9 | 10 | This is currently in a "beta" state. There may be unfinished features, UI glitches, race conditions, crashes etc. Feedback is needed to imporove the project. Please use github issues with any questions, problems, or requests. 11 | 12 | [ demo](https://www.youtube.com/watch?v=uXhqEe8Kw6M&list=PLvpLfzys-jPumkXZj8ZZn11zyY3UYtSkn&index=6) 13 | [latest frontend release](http://espels.s3-us-west-2.amazonaws.com/release_0_0_3/index.html) 14 | 15 | ## Features 16 | 17 | * Imperial or Metric 18 | * Revolution counter 19 | * Feed Mode: 20 | * Acts like a full time gear system for the leadscrew (like clough42's ELS) 21 | * MoveSync Mode: 22 | * Allows you to feed a fixed distance and stop 23 | * Bounce Mode: 24 | * Feeds at a cutting speed and then rapids back to the starting position 25 | 26 | ### Planned Features 27 | 28 | 29 | * Spindle angle DRO indicator 30 | * Broaching mode 31 | * Utilize bounce mode with spindle fixed for broaching keyways. 32 | * Virtual compound threading mode 33 | * This mode will offset threading passes to simulate a compound's angle infeed 34 | * TPI presets 35 | * General Presets ( ala touchDRO) 36 | * Hobbing Mode 37 | * Reuse codebase for configuring and running my hobbing controller 38 | 39 | ## Configuration 40 | 41 | Copy config.ini.d to config.ini 42 | 43 | In config.ini update the WIFI_SSID, WIFI_PASSWORD Z_STEP_PIN, Z_DIR_PIN, EA, and EB for your encoder signals etc. 44 | 45 | The webUI simply is a react.js application designed to be responsive, it can live anywhere and should run on your phone, tablet, laptop or PC. It connects to the firmware via websockets. No network out to the internets is needed. The s3 links are simply for convienence, you can serve the frontend yourself by copying the index.html or running `HOST=0.0.0.0 npm start`. I may eventually offer an option to serve it from esp32's directly (assuming there is flash available). 46 | 47 | Once the firware is flashed you simply need to configure the frontend with the IP or dns of the firmware. 48 | 49 | ![image](https://user-images.githubusercontent.com/20271/225640770-0720b314-eee3-4650-9613-717a55c63898.png) 50 | 51 | 52 | After that the "wifi" icon will turn from red to green once connected. You may want to continue to monitor the firmware's serial output the first time you connect. You will see something like this: 53 | 54 | ![image](https://user-images.githubusercontent.com/20271/225632806-9f107f18-0247-4377-a290-8d14f369b59e.png) 55 | 56 | Next you can click the red "venc On" button. This will turn on a virtual quadrature encoder to simulate the spindle moving. You will see the RPM: DRO field increase and the rev indicator will show the number of revolutions. 57 | 58 | Finally click the "Selected Mode" dropdown to change the mode, select Feed Mode, or MoveSync Mode, change the parameters (pitch etc) and test away! 59 | 60 | ![image](https://user-images.githubusercontent.com/20271/225641162-c13e5c4c-d1a8-48b6-bdbc-2bdc5bf3bffc.png) 61 | 62 | 63 | ## Lathe Setup 64 | 65 | When installing on a lathe you will need an encoder with enough resolution. Testing has been done with a 600PPI -- 2400CPI encoder. While more encoder pulses will create more accuracy the algorithm used is limited to a max of 1 step per 1 encoder position. This limits the maximum pitch you can synchronize. Consider this and the maximum thread pitch your lathe can handle when selecting an encoder and stepper microstepping configuration. 66 | 67 | 68 | A closed loop stepper is highly recommended. The stepper online 1-CL57Y-24HE40 is a good kit for a small hobby lathe. 69 | 70 | 71 | You may need to swap your encoder pins and or change your stepper driver's direction. The expectation is that when the spindle turns counter clockwise the "left" buttons should move the carriage Z-. 72 | 73 | 74 | ## Frontend 75 | 76 | the webfrontend can be found here [https://github.com/jschoch/espELSfrontend] 77 | 78 | ## HOW 79 | 80 | Initially I was planning on making a pcb with buttons to control everything. This is messy and hard to update. Now I'm using websockets and a react SPA to control everything. The websockets transmit json and msgPack for configuration and status updates. This is working very nicely. 81 | 82 | This is currently using a version of the "didge" algorythm here (https://github.com/prototypicall/Didge/blob/master/doc/How.md_). The slope can't be > 1 so you may need to reduce your micro stepping to facilitate large thread pitches. 83 | 84 | 85 | 86 | -------------------------------------------------------------------------------- /TODO.md: -------------------------------------------------------------------------------- 1 | Critical 2 | - [ ] Bounce enters unknown mode, and is broken after moveCancel issues 3 | - [ ] Bounce may work unexpectedly when spindle is running in reverse 4 | - [ ] Add wifi reconnect logic 5 | - [ ] optional LED's, particularly for wifi connection status 6 | 7 | 8 | 9 | Rest 10 | 11 | ** TODO 12 | 13 | - [ ] lock UI on rapid move 14 | - [ ] add rapid cancel 15 | - [ ] Add physical stops (adjustable hall sensors for example) 16 | - [ ] Add backlash compensation 17 | - [ ] turn on task monitoring and display via web ui 18 | - [ ] smooth filter EMA RPM for display 19 | - [ ] Add angle measure mode like a manual turned indexing plate. 20 | -------------------------------------------------------------------------------- /config.ini.template.ini: -------------------------------------------------------------------------------- 1 | [env:ESPels] 2 | #port that platformio will use to upload over usb 3 | upload_port = COM3 4 | 5 | build_src_flags = 6 | #machine configuration 7 | '-D HOSTNAME="mx210lathe"' 8 | -D LEADSCREW_LEAD=2.0 9 | '-D WIFI_SSID="yourssidhere"' 10 | '-D WIFI_PASSWORD="yourwifipassword"' 11 | #motor configuration 12 | -D Z_STEP_PIN=13 13 | -D Z_DIR_PIN=12 14 | -D Z_NATIVE_STEPS_PER_REV=200 15 | -D Z_MICROSTEPPING=8 16 | #Spindle Encoder pins 17 | -D EA=25 18 | -D EB=26 19 | #choices are: 20 | #EXTERN //your hardware handles the pullup or pulldown, for example with a resistor to 3v3 or to gnd 21 | #INTERN_PULLDOWN //your encoder expects the MCU to pull low, and sends a high for a pulse 22 | #INTERN_PULLUP //your esp handles the pullup and your encoder pulls it down. 23 | #For most common quadrature encoders, choose Extern and apply 3.3v to your encoder pins through 1.5k to 4.7k ohm resistors */ 24 | -D ENCODER_PULLUP_TYPE=EXTERN 25 | #ENCODER_QUADRATURE_MODE should be ON, unless you have a good reason not to. Otherwise your leadscrew will not track reverses. 26 | #valid values: ON, OFF 27 | -D ENCODER_QUADRATURE_MODE=ON 28 | -D ENCODER_RESOLUTION=2400 #this is counts per rev *4 for a quadrature encoder 29 | -D USESSD1306=1 #use the display or not. Recommend not, it doesn't have much functionality. Set to 1 to enable. 30 | -D error_led=21 31 | -D wifi_led=32 32 | -D configured=true #ignore this, this just tells the config that you've configured your machine 33 | 34 | [env:ota] 35 | #ip address of the esp when connected to your wifi, if you want to upload firmware remotely 36 | upload_port = 192.168.0.187 37 | 38 | [env:ESPelsOTA] 39 | #ip address of the esp when connected to your wifi, if you want to upload firmware remotely 40 | upload_port = 192.168.1.28 41 | -------------------------------------------------------------------------------- /include/README: -------------------------------------------------------------------------------- 1 | 2 | This directory is intended for project header files. 3 | 4 | A header file is a file containing C declarations and macro definitions 5 | to be shared between several project source files. You request the use of a 6 | header file in your project source file (C, C++, etc) located in `src` folder 7 | by including it, with the C preprocessing directive `#include'. 8 | 9 | ```src/main.c 10 | 11 | #include "header.h" 12 | 13 | int main (void) 14 | { 15 | ... 16 | } 17 | ``` 18 | 19 | Including a header file produces the same results as copying the header file 20 | into each source file that needs it. Such copying would be time-consuming 21 | and error-prone. With a header file, the related declarations appear 22 | in only one place. If they need to be changed, they can be changed in one 23 | place, and programs that include the header file will automatically use the 24 | new version when next recompiled. The header file eliminates the labor of 25 | finding and changing all the copies as well as the risk that a failure to 26 | find one copy will result in inconsistencies within a program. 27 | 28 | In C, the usual convention is to give header files names that end with `.h'. 29 | It is most portable to use only letters, digits, dashes, and underscores in 30 | header file names, and at most one dot. 31 | 32 | Read more about using header files in official GCC documentation: 33 | 34 | * Include Syntax 35 | * Include Operation 36 | * Once-Only Headers 37 | * Computed Includes 38 | 39 | https://gcc.gnu.org/onlinedocs/cpp/Header-Files.html 40 | -------------------------------------------------------------------------------- /lib/.foo: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/jschoch/ESPels/c20d9ba7d2f227a75d2c5b8b9108a3e80a8d6d8d/lib/.foo -------------------------------------------------------------------------------- /nativeStatic.py: -------------------------------------------------------------------------------- 1 | Import("env") 2 | 3 | # 4 | # Dump build environment (for debug) 5 | # print(env.Dump()) 6 | # 7 | 8 | env.Append( 9 | LINKFLAGS=[ 10 | "-static", 11 | "-static-libgcc", 12 | "-static-libstdc++" 13 | ] 14 | ) 15 | -------------------------------------------------------------------------------- /platformio.ini: -------------------------------------------------------------------------------- 1 | 2 | [platformio] 3 | extra_configs = config.ini 4 | 5 | [env:ESPels] 6 | platform = espressif32 7 | board = esp32dev 8 | framework = arduino 9 | monitor_speed = 115200 10 | lib_deps = 11 | gin66/FastAccelStepper@^0.28.3 12 | thingpulse/ESP8266 and ESP32 OLED driver for SSD1306 displays@^4.3.0 13 | thomasfredericks/Bounce2@^2.55 14 | bricofoy/YASM@^1.0.4 15 | https://github.com/me-no-dev/ESPAsyncWebServer.git 16 | bblanchon/ArduinoJson@^6.19.4 17 | bblanchon/StreamUtils@^1.6.3 18 | madhephaestus/ESP32Encoder@~0.10.1 19 | monitor_filters = esp32_exception_decoder 20 | build_flags = -DCORE_DEBUG_LEVEL=3 -DLOG_LOCAL_LEVEL=ESP_LOG_DEBUG -Wall -Wextra -Wunused 21 | check_tool = cppcheck 22 | check_flags = -v 23 | check_skip_packages = yes 24 | 25 | [env:ota_debug] 26 | extends = env:ESPels 27 | build_flags = 28 | -D CORE_DEBUG_LEVEL=ARDUHAL_LOG_LEVEL_VERBOSE 29 | -D LOG_LEVEL=LOG_LEVEL_VERBOSE 30 | build_type = debug 31 | 32 | [env:ESPelsOTA] 33 | extends = env:ESPels 34 | upload_protocol = espota 35 | upload_port = ${env:ota.upload_port} 36 | 37 | [env:cppchecker] 38 | platform = espressif32 39 | board = esp32dev 40 | framework = arduino 41 | extends = env:ESPels 42 | check_skip_packages = yes 43 | check_flags = 44 | cppcheck: --language=c++ --suppress=*:*pio\* --suppress=*:*neotimer\* 45 | check_patterns= 46 | ./src 47 | 48 | [env:ctd] 49 | platform = espressif32 50 | board = esp32dev 51 | framework = arduino 52 | extends = env:ESPels 53 | check_tool = clangtidy 54 | check_skip_packages = yes 55 | check_patterns = 56 | src 57 | 58 | 59 | 60 | [env:ESPelsTest] 61 | platform = native 62 | check_flags = --verbose --enable=all --std=c++11 63 | extra_scripts = 64 | nativeStatic.py 65 | lib_deps = 66 | ArduinoFake 67 | gin66/FastAccelStepper@^0.28.3 68 | thingpulse/ESP8266 and ESP32 OLED driver for SSD1306 displays@^4.3.0 69 | thomasfredericks/Bounce2@^2.55 70 | bricofoy/YASM@^1.0.4 71 | https://github.com/me-no-dev/ESPAsyncWebServer.git 72 | bblanchon/ArduinoJson@^6.19.4 73 | bblanchon/StreamUtils@^1.6.3 74 | debug_test = test_stepper 75 | 76 | 77 | -------------------------------------------------------------------------------- /sdkconfig: -------------------------------------------------------------------------------- 1 | # 2 | # Automatically generated file. DO NOT EDIT. 3 | # Espressif IoT Development Framework (ESP-IDF) Project Configuration 4 | # 5 | CONFIG_SOC_BROWNOUT_RESET_SUPPORTED="Not determined" 6 | CONFIG_SOC_TWAI_BRP_DIV_SUPPORTED="Not determined" 7 | CONFIG_SOC_DPORT_WORKAROUND="Not determined" 8 | CONFIG_SOC_CAPS_ECO_VER_MAX=3 9 | CONFIG_SOC_ADC_SUPPORTED=y 10 | CONFIG_SOC_DAC_SUPPORTED=y 11 | CONFIG_SOC_MCPWM_SUPPORTED=y 12 | CONFIG_SOC_SDMMC_HOST_SUPPORTED=y 13 | CONFIG_SOC_BT_SUPPORTED=y 14 | CONFIG_SOC_PCNT_SUPPORTED=y 15 | CONFIG_SOC_WIFI_SUPPORTED=y 16 | CONFIG_SOC_SDIO_SLAVE_SUPPORTED=y 17 | CONFIG_SOC_TWAI_SUPPORTED=y 18 | CONFIG_SOC_EMAC_SUPPORTED=y 19 | CONFIG_SOC_ULP_SUPPORTED=y 20 | CONFIG_SOC_CCOMP_TIMER_SUPPORTED=y 21 | CONFIG_SOC_RTC_FAST_MEM_SUPPORTED=y 22 | CONFIG_SOC_RTC_SLOW_MEM_SUPPORTED=y 23 | CONFIG_SOC_RTC_MEM_SUPPORTED=y 24 | CONFIG_SOC_I2S_SUPPORTED=y 25 | CONFIG_SOC_RMT_SUPPORTED=y 26 | CONFIG_SOC_SDM_SUPPORTED=y 27 | CONFIG_SOC_SUPPORT_COEXISTENCE=y 28 | CONFIG_SOC_AES_SUPPORTED=y 29 | CONFIG_SOC_MPI_SUPPORTED=y 30 | CONFIG_SOC_SHA_SUPPORTED=y 31 | CONFIG_SOC_FLASH_ENC_SUPPORTED=y 32 | CONFIG_SOC_SECURE_BOOT_SUPPORTED=y 33 | CONFIG_SOC_TOUCH_SENSOR_SUPPORTED=y 34 | CONFIG_SOC_DPORT_WORKAROUND_DIS_INTERRUPT_LVL=5 35 | CONFIG_SOC_XTAL_SUPPORT_26M=y 36 | CONFIG_SOC_XTAL_SUPPORT_40M=y 37 | CONFIG_SOC_XTAL_SUPPORT_AUTO_DETECT=y 38 | CONFIG_SOC_ADC_RTC_CTRL_SUPPORTED=y 39 | CONFIG_SOC_ADC_DIG_CTRL_SUPPORTED=y 40 | CONFIG_SOC_ADC_DMA_SUPPORTED=y 41 | CONFIG_SOC_ADC_PERIPH_NUM=2 42 | CONFIG_SOC_ADC_MAX_CHANNEL_NUM=10 43 | CONFIG_SOC_ADC_ATTEN_NUM=4 44 | CONFIG_SOC_ADC_DIGI_CONTROLLER_NUM=2 45 | CONFIG_SOC_ADC_PATT_LEN_MAX=16 46 | CONFIG_SOC_ADC_DIGI_MIN_BITWIDTH=9 47 | CONFIG_SOC_ADC_DIGI_MAX_BITWIDTH=12 48 | CONFIG_SOC_ADC_DIGI_RESULT_BYTES=2 49 | CONFIG_SOC_ADC_DIGI_DATA_BYTES_PER_CONV=4 50 | CONFIG_SOC_ADC_SAMPLE_FREQ_THRES_HIGH=2 51 | CONFIG_SOC_ADC_SAMPLE_FREQ_THRES_LOW=20 52 | CONFIG_SOC_ADC_RTC_MIN_BITWIDTH=9 53 | CONFIG_SOC_ADC_RTC_MAX_BITWIDTH=12 54 | CONFIG_SOC_RTC_SLOW_CLOCK_SUPPORT_8MD256=y 55 | CONFIG_SOC_SHARED_IDCACHE_SUPPORTED=y 56 | CONFIG_SOC_MMU_LINEAR_ADDRESS_REGION_NUM=5 57 | CONFIG_SOC_CPU_CORES_NUM=2 58 | CONFIG_SOC_CPU_INTR_NUM=32 59 | CONFIG_SOC_CPU_HAS_FPU=y 60 | CONFIG_SOC_CPU_BREAKPOINTS_NUM=2 61 | CONFIG_SOC_CPU_WATCHPOINTS_NUM=2 62 | CONFIG_SOC_CPU_WATCHPOINT_SIZE=64 63 | CONFIG_SOC_DAC_PERIPH_NUM=2 64 | CONFIG_SOC_DAC_RESOLUTION=8 65 | CONFIG_SOC_GPIO_PORT=1 66 | CONFIG_SOC_GPIO_PIN_COUNT=40 67 | CONFIG_SOC_GPIO_VALID_GPIO_MASK=0xFFFFFFFFFF 68 | CONFIG_SOC_GPIO_SUPPORT_SLP_SWITCH=y 69 | CONFIG_SOC_I2C_NUM=2 70 | CONFIG_SOC_I2C_FIFO_LEN=32 71 | CONFIG_SOC_I2C_SUPPORT_SLAVE=y 72 | CONFIG_SOC_I2C_SUPPORT_APB=y 73 | CONFIG_SOC_CLK_APLL_SUPPORTED=y 74 | CONFIG_SOC_APLL_MULTIPLIER_OUT_MIN_HZ=350000000 75 | CONFIG_SOC_APLL_MULTIPLIER_OUT_MAX_HZ=500000000 76 | CONFIG_SOC_APLL_MIN_HZ=5303031 77 | CONFIG_SOC_APLL_MAX_HZ=125000000 78 | CONFIG_SOC_I2S_NUM=2 79 | CONFIG_SOC_I2S_HW_VERSION_1=y 80 | CONFIG_SOC_I2S_SUPPORTS_APLL=y 81 | CONFIG_SOC_I2S_SUPPORTS_PDM=y 82 | CONFIG_SOC_I2S_SUPPORTS_PDM_TX=y 83 | CONFIG_SOC_I2S_SUPPORTS_PDM_RX=y 84 | CONFIG_SOC_I2S_SUPPORTS_ADC_DAC=y 85 | CONFIG_SOC_I2S_SUPPORTS_ADC=y 86 | CONFIG_SOC_I2S_SUPPORTS_DAC=y 87 | CONFIG_SOC_I2S_SUPPORTS_LCD_CAMERA=y 88 | CONFIG_SOC_I2S_TRANS_SIZE_ALIGN_WORD=y 89 | CONFIG_SOC_I2S_LCD_I80_VARIANT=y 90 | CONFIG_SOC_LCD_I80_SUPPORTED=y 91 | CONFIG_SOC_LCD_I80_BUSES=2 92 | CONFIG_SOC_LCD_I80_BUS_WIDTH=24 93 | CONFIG_SOC_LEDC_HAS_TIMER_SPECIFIC_MUX=y 94 | CONFIG_SOC_LEDC_SUPPORT_APB_CLOCK=y 95 | CONFIG_SOC_LEDC_SUPPORT_REF_TICK=y 96 | CONFIG_SOC_LEDC_SUPPORT_HS_MODE=y 97 | CONFIG_SOC_LEDC_CHANNEL_NUM=8 98 | CONFIG_SOC_LEDC_TIMER_BIT_WIDE_NUM=20 99 | CONFIG_SOC_MCPWM_GROUPS=2 100 | CONFIG_SOC_MCPWM_TIMERS_PER_GROUP=3 101 | CONFIG_SOC_MCPWM_OPERATORS_PER_GROUP=3 102 | CONFIG_SOC_MCPWM_COMPARATORS_PER_OPERATOR=2 103 | CONFIG_SOC_MCPWM_GENERATORS_PER_OPERATOR=2 104 | CONFIG_SOC_MCPWM_TRIGGERS_PER_OPERATOR=2 105 | CONFIG_SOC_MCPWM_GPIO_FAULTS_PER_GROUP=3 106 | CONFIG_SOC_MCPWM_CAPTURE_TIMERS_PER_GROUP=y 107 | CONFIG_SOC_MCPWM_CAPTURE_CHANNELS_PER_TIMER=3 108 | CONFIG_SOC_MCPWM_GPIO_SYNCHROS_PER_GROUP=3 109 | CONFIG_SOC_MPU_MIN_REGION_SIZE=0x20000000 110 | CONFIG_SOC_MPU_REGIONS_MAX_NUM=8 111 | CONFIG_SOC_PCNT_GROUPS=1 112 | CONFIG_SOC_PCNT_UNITS_PER_GROUP=8 113 | CONFIG_SOC_PCNT_CHANNELS_PER_UNIT=2 114 | CONFIG_SOC_PCNT_THRES_POINT_PER_UNIT=2 115 | CONFIG_SOC_RMT_GROUPS=1 116 | CONFIG_SOC_RMT_TX_CANDIDATES_PER_GROUP=8 117 | CONFIG_SOC_RMT_RX_CANDIDATES_PER_GROUP=8 118 | CONFIG_SOC_RMT_CHANNELS_PER_GROUP=8 119 | CONFIG_SOC_RMT_MEM_WORDS_PER_CHANNEL=64 120 | CONFIG_SOC_RMT_SUPPORT_REF_TICK=y 121 | CONFIG_SOC_RMT_SUPPORT_APB=y 122 | CONFIG_SOC_RMT_CHANNEL_CLK_INDEPENDENT=y 123 | CONFIG_SOC_RTCIO_PIN_COUNT=18 124 | CONFIG_SOC_RTCIO_INPUT_OUTPUT_SUPPORTED=y 125 | CONFIG_SOC_RTCIO_HOLD_SUPPORTED=y 126 | CONFIG_SOC_RTCIO_WAKE_SUPPORTED=y 127 | CONFIG_SOC_SDM_GROUPS=1 128 | CONFIG_SOC_SDM_CHANNELS_PER_GROUP=8 129 | CONFIG_SOC_SPI_HD_BOTH_INOUT_SUPPORTED=y 130 | CONFIG_SOC_SPI_AS_CS_SUPPORTED=y 131 | CONFIG_SOC_SPI_PERIPH_NUM=3 132 | CONFIG_SOC_SPI_DMA_CHAN_NUM=2 133 | CONFIG_SOC_SPI_MAX_CS_NUM=3 134 | CONFIG_SOC_SPI_MAXIMUM_BUFFER_SIZE=64 135 | CONFIG_SOC_SPI_MAX_PRE_DIVIDER=8192 136 | CONFIG_SOC_MEMSPI_SRC_FREQ_80M_SUPPORTED=y 137 | CONFIG_SOC_MEMSPI_SRC_FREQ_40M_SUPPORTED=y 138 | CONFIG_SOC_MEMSPI_SRC_FREQ_26M_SUPPORTED=y 139 | CONFIG_SOC_MEMSPI_SRC_FREQ_20M_SUPPORTED=y 140 | CONFIG_SOC_TIMER_GROUPS=2 141 | CONFIG_SOC_TIMER_GROUP_TIMERS_PER_GROUP=2 142 | CONFIG_SOC_TIMER_GROUP_COUNTER_BIT_WIDTH=64 143 | CONFIG_SOC_TIMER_GROUP_TOTAL_TIMERS=4 144 | CONFIG_SOC_TIMER_GROUP_SUPPORT_APB=y 145 | CONFIG_SOC_TOUCH_VERSION_1=y 146 | CONFIG_SOC_TOUCH_SENSOR_NUM=10 147 | CONFIG_SOC_TOUCH_PAD_MEASURE_WAIT_MAX=0xFF 148 | CONFIG_SOC_TWAI_BRP_MIN=2 149 | CONFIG_SOC_TWAI_SUPPORT_MULTI_ADDRESS_LAYOUT=y 150 | CONFIG_SOC_UART_NUM=3 151 | CONFIG_SOC_UART_SUPPORT_APB_CLK=y 152 | CONFIG_SOC_UART_SUPPORT_REF_TICK=y 153 | CONFIG_SOC_UART_FIFO_LEN=128 154 | CONFIG_SOC_UART_BITRATE_MAX=5000000 155 | CONFIG_SOC_SPIRAM_SUPPORTED=y 156 | CONFIG_SOC_SPI_MEM_SUPPORT_CONFIG_GPIO_BY_EFUSE=y 157 | CONFIG_SOC_SHA_SUPPORT_PARALLEL_ENG=y 158 | CONFIG_SOC_SHA_SUPPORT_SHA1=y 159 | CONFIG_SOC_SHA_SUPPORT_SHA256=y 160 | CONFIG_SOC_SHA_SUPPORT_SHA384=y 161 | CONFIG_SOC_SHA_SUPPORT_SHA512=y 162 | CONFIG_SOC_RSA_MAX_BIT_LEN=4096 163 | CONFIG_SOC_AES_SUPPORT_AES_128=y 164 | CONFIG_SOC_AES_SUPPORT_AES_192=y 165 | CONFIG_SOC_AES_SUPPORT_AES_256=y 166 | CONFIG_SOC_SECURE_BOOT_V1=y 167 | CONFIG_SOC_EFUSE_SECURE_BOOT_KEY_DIGESTS=y 168 | CONFIG_SOC_FLASH_ENCRYPTED_XTS_AES_BLOCK_MAX=32 169 | CONFIG_SOC_PHY_DIG_REGS_MEM_SIZE=21 170 | CONFIG_SOC_PM_SUPPORT_EXT_WAKEUP=y 171 | CONFIG_SOC_PM_SUPPORT_TOUCH_SENSOR_WAKEUP=y 172 | CONFIG_SOC_PM_SUPPORT_RTC_PERIPH_PD=y 173 | CONFIG_SOC_PM_SUPPORT_RTC_FAST_MEM_PD=y 174 | CONFIG_SOC_PM_SUPPORT_RTC_SLOW_MEM_PD=y 175 | CONFIG_SOC_SDMMC_USE_IOMUX=y 176 | CONFIG_SOC_SDMMC_NUM_SLOTS=2 177 | CONFIG_SOC_WIFI_WAPI_SUPPORT=y 178 | CONFIG_SOC_WIFI_CSI_SUPPORT=y 179 | CONFIG_SOC_WIFI_MESH_SUPPORT=y 180 | CONFIG_SOC_BLE_SUPPORTED=y 181 | CONFIG_SOC_BLE_MESH_SUPPORTED=y 182 | CONFIG_SOC_BT_CLASSIC_SUPPORTED=y 183 | CONFIG_IDF_CMAKE=y 184 | CONFIG_IDF_TARGET_ARCH_XTENSA=y 185 | CONFIG_IDF_TARGET_ARCH="xtensa" 186 | CONFIG_IDF_TARGET="esp32" 187 | CONFIG_IDF_TARGET_ESP32=y 188 | CONFIG_IDF_FIRMWARE_CHIP_ID=0x0000 189 | 190 | # 191 | # Build type 192 | # 193 | CONFIG_APP_BUILD_TYPE_APP_2NDBOOT=y 194 | # CONFIG_APP_BUILD_TYPE_ELF_RAM is not set 195 | CONFIG_APP_BUILD_GENERATE_BINARIES=y 196 | CONFIG_APP_BUILD_BOOTLOADER=y 197 | CONFIG_APP_BUILD_USE_FLASH_SECTIONS=y 198 | # CONFIG_APP_REPRODUCIBLE_BUILD is not set 199 | # CONFIG_APP_NO_BLOBS is not set 200 | # CONFIG_APP_COMPATIBLE_PRE_V2_1_BOOTLOADERS is not set 201 | # CONFIG_APP_COMPATIBLE_PRE_V3_1_BOOTLOADERS is not set 202 | # end of Build type 203 | 204 | # 205 | # Bootloader config 206 | # 207 | CONFIG_BOOTLOADER_OFFSET_IN_FLASH=0x1000 208 | CONFIG_BOOTLOADER_COMPILER_OPTIMIZATION_SIZE=y 209 | # CONFIG_BOOTLOADER_COMPILER_OPTIMIZATION_DEBUG is not set 210 | # CONFIG_BOOTLOADER_COMPILER_OPTIMIZATION_PERF is not set 211 | # CONFIG_BOOTLOADER_COMPILER_OPTIMIZATION_NONE is not set 212 | # CONFIG_BOOTLOADER_LOG_LEVEL_NONE is not set 213 | # CONFIG_BOOTLOADER_LOG_LEVEL_ERROR is not set 214 | # CONFIG_BOOTLOADER_LOG_LEVEL_WARN is not set 215 | CONFIG_BOOTLOADER_LOG_LEVEL_INFO=y 216 | # CONFIG_BOOTLOADER_LOG_LEVEL_DEBUG is not set 217 | # CONFIG_BOOTLOADER_LOG_LEVEL_VERBOSE is not set 218 | CONFIG_BOOTLOADER_LOG_LEVEL=3 219 | # CONFIG_BOOTLOADER_VDDSDIO_BOOST_1_8V is not set 220 | CONFIG_BOOTLOADER_VDDSDIO_BOOST_1_9V=y 221 | # CONFIG_BOOTLOADER_FACTORY_RESET is not set 222 | # CONFIG_BOOTLOADER_APP_TEST is not set 223 | CONFIG_BOOTLOADER_REGION_PROTECTION_ENABLE=y 224 | CONFIG_BOOTLOADER_WDT_ENABLE=y 225 | # CONFIG_BOOTLOADER_WDT_DISABLE_IN_USER_CODE is not set 226 | CONFIG_BOOTLOADER_WDT_TIME_MS=9000 227 | # CONFIG_BOOTLOADER_APP_ROLLBACK_ENABLE is not set 228 | # CONFIG_BOOTLOADER_SKIP_VALIDATE_IN_DEEP_SLEEP is not set 229 | # CONFIG_BOOTLOADER_SKIP_VALIDATE_ON_POWER_ON is not set 230 | # CONFIG_BOOTLOADER_SKIP_VALIDATE_ALWAYS is not set 231 | CONFIG_BOOTLOADER_RESERVE_RTC_SIZE=0 232 | # CONFIG_BOOTLOADER_CUSTOM_RESERVE_RTC is not set 233 | CONFIG_BOOTLOADER_FLASH_XMC_SUPPORT=y 234 | # end of Bootloader config 235 | 236 | # 237 | # Security features 238 | # 239 | CONFIG_SECURE_BOOT_V1_SUPPORTED=y 240 | # CONFIG_SECURE_SIGNED_APPS_NO_SECURE_BOOT is not set 241 | # CONFIG_SECURE_BOOT is not set 242 | # CONFIG_SECURE_FLASH_ENC_ENABLED is not set 243 | # end of Security features 244 | 245 | # 246 | # Application manager 247 | # 248 | CONFIG_APP_COMPILE_TIME_DATE=y 249 | # CONFIG_APP_EXCLUDE_PROJECT_VER_VAR is not set 250 | # CONFIG_APP_EXCLUDE_PROJECT_NAME_VAR is not set 251 | # CONFIG_APP_PROJECT_VER_FROM_CONFIG is not set 252 | CONFIG_APP_RETRIEVE_LEN_ELF_SHA=16 253 | # end of Application manager 254 | 255 | CONFIG_ESP_ROM_HAS_CRC_LE=y 256 | CONFIG_ESP_ROM_HAS_CRC_BE=y 257 | CONFIG_ESP_ROM_HAS_JPEG_DECODE=y 258 | CONFIG_ESP_ROM_SUPPORT_MULTIPLE_UART=y 259 | CONFIG_ESP_ROM_NEEDS_SWSETUP_WORKAROUND=y 260 | 261 | # 262 | # Serial flasher config 263 | # 264 | # CONFIG_ESPTOOLPY_NO_STUB is not set 265 | # CONFIG_ESPTOOLPY_FLASHMODE_QIO is not set 266 | # CONFIG_ESPTOOLPY_FLASHMODE_QOUT is not set 267 | CONFIG_ESPTOOLPY_FLASHMODE_DIO=y 268 | # CONFIG_ESPTOOLPY_FLASHMODE_DOUT is not set 269 | CONFIG_ESPTOOLPY_FLASH_SAMPLE_MODE_STR=y 270 | CONFIG_ESPTOOLPY_FLASHMODE="dio" 271 | # CONFIG_ESPTOOLPY_FLASHFREQ_80M is not set 272 | CONFIG_ESPTOOLPY_FLASHFREQ_40M=y 273 | # CONFIG_ESPTOOLPY_FLASHFREQ_26M is not set 274 | # CONFIG_ESPTOOLPY_FLASHFREQ_20M is not set 275 | CONFIG_ESPTOOLPY_FLASHFREQ="40m" 276 | # CONFIG_ESPTOOLPY_FLASHSIZE_1MB is not set 277 | CONFIG_ESPTOOLPY_FLASHSIZE_2MB=y 278 | # CONFIG_ESPTOOLPY_FLASHSIZE_4MB is not set 279 | # CONFIG_ESPTOOLPY_FLASHSIZE_8MB is not set 280 | # CONFIG_ESPTOOLPY_FLASHSIZE_16MB is not set 281 | # CONFIG_ESPTOOLPY_FLASHSIZE_32MB is not set 282 | # CONFIG_ESPTOOLPY_FLASHSIZE_64MB is not set 283 | # CONFIG_ESPTOOLPY_FLASHSIZE_128MB is not set 284 | CONFIG_ESPTOOLPY_FLASHSIZE="2MB" 285 | # CONFIG_ESPTOOLPY_HEADER_FLASHSIZE_UPDATE is not set 286 | CONFIG_ESPTOOLPY_BEFORE_RESET=y 287 | # CONFIG_ESPTOOLPY_BEFORE_NORESET is not set 288 | CONFIG_ESPTOOLPY_BEFORE="default_reset" 289 | CONFIG_ESPTOOLPY_AFTER_RESET=y 290 | # CONFIG_ESPTOOLPY_AFTER_NORESET is not set 291 | CONFIG_ESPTOOLPY_AFTER="hard_reset" 292 | CONFIG_ESPTOOLPY_MONITOR_BAUD=115200 293 | # end of Serial flasher config 294 | 295 | # 296 | # Partition Table 297 | # 298 | CONFIG_PARTITION_TABLE_SINGLE_APP=y 299 | # CONFIG_PARTITION_TABLE_SINGLE_APP_LARGE is not set 300 | # CONFIG_PARTITION_TABLE_TWO_OTA is not set 301 | # CONFIG_PARTITION_TABLE_CUSTOM is not set 302 | CONFIG_PARTITION_TABLE_CUSTOM_FILENAME="partitions.csv" 303 | CONFIG_PARTITION_TABLE_FILENAME="partitions_singleapp.csv" 304 | CONFIG_PARTITION_TABLE_OFFSET=0x8000 305 | CONFIG_PARTITION_TABLE_MD5=y 306 | # end of Partition Table 307 | 308 | # 309 | # Compiler options 310 | # 311 | CONFIG_COMPILER_OPTIMIZATION_DEFAULT=y 312 | # CONFIG_COMPILER_OPTIMIZATION_SIZE is not set 313 | # CONFIG_COMPILER_OPTIMIZATION_PERF is not set 314 | # CONFIG_COMPILER_OPTIMIZATION_NONE is not set 315 | CONFIG_COMPILER_OPTIMIZATION_ASSERTIONS_ENABLE=y 316 | # CONFIG_COMPILER_OPTIMIZATION_ASSERTIONS_SILENT is not set 317 | # CONFIG_COMPILER_OPTIMIZATION_ASSERTIONS_DISABLE is not set 318 | CONFIG_COMPILER_FLOAT_LIB_FROM_GCCLIB=y 319 | CONFIG_COMPILER_OPTIMIZATION_ASSERTION_LEVEL=2 320 | # CONFIG_COMPILER_OPTIMIZATION_CHECKS_SILENT is not set 321 | CONFIG_COMPILER_HIDE_PATHS_MACROS=y 322 | # CONFIG_COMPILER_CXX_EXCEPTIONS is not set 323 | # CONFIG_COMPILER_CXX_RTTI is not set 324 | CONFIG_COMPILER_STACK_CHECK_MODE_NONE=y 325 | # CONFIG_COMPILER_STACK_CHECK_MODE_NORM is not set 326 | # CONFIG_COMPILER_STACK_CHECK_MODE_STRONG is not set 327 | # CONFIG_COMPILER_STACK_CHECK_MODE_ALL is not set 328 | # CONFIG_COMPILER_WARN_WRITE_STRINGS is not set 329 | # CONFIG_COMPILER_DUMP_RTL_FILES is not set 330 | # end of Compiler options 331 | 332 | # 333 | # Component config 334 | # 335 | 336 | # 337 | # Application Level Tracing 338 | # 339 | # CONFIG_APPTRACE_DEST_JTAG is not set 340 | CONFIG_APPTRACE_DEST_NONE=y 341 | # CONFIG_APPTRACE_DEST_UART1 is not set 342 | # CONFIG_APPTRACE_DEST_UART2 is not set 343 | CONFIG_APPTRACE_DEST_UART_NONE=y 344 | CONFIG_APPTRACE_UART_TASK_PRIO=1 345 | CONFIG_APPTRACE_LOCK_ENABLE=y 346 | # end of Application Level Tracing 347 | 348 | # 349 | # Bluetooth 350 | # 351 | # CONFIG_BT_ENABLED is not set 352 | # end of Bluetooth 353 | 354 | # 355 | # Driver Configurations 356 | # 357 | 358 | # 359 | # Legacy ADC Configuration 360 | # 361 | CONFIG_ADC_DISABLE_DAC=y 362 | # CONFIG_ADC_SUPPRESS_DEPRECATE_WARN is not set 363 | 364 | # 365 | # Legacy ADC Calibration Configuration 366 | # 367 | CONFIG_ADC_CAL_EFUSE_TP_ENABLE=y 368 | CONFIG_ADC_CAL_EFUSE_VREF_ENABLE=y 369 | CONFIG_ADC_CAL_LUT_ENABLE=y 370 | # CONFIG_ADC_CALI_SUPPRESS_DEPRECATE_WARN is not set 371 | # end of Legacy ADC Calibration Configuration 372 | # end of Legacy ADC Configuration 373 | 374 | # 375 | # SPI Configuration 376 | # 377 | # CONFIG_SPI_MASTER_IN_IRAM is not set 378 | CONFIG_SPI_MASTER_ISR_IN_IRAM=y 379 | # CONFIG_SPI_SLAVE_IN_IRAM is not set 380 | CONFIG_SPI_SLAVE_ISR_IN_IRAM=y 381 | # end of SPI Configuration 382 | 383 | # 384 | # TWAI Configuration 385 | # 386 | # CONFIG_TWAI_ISR_IN_IRAM is not set 387 | CONFIG_TWAI_ERRATA_FIX_BUS_OFF_REC=y 388 | CONFIG_TWAI_ERRATA_FIX_TX_INTR_LOST=y 389 | CONFIG_TWAI_ERRATA_FIX_RX_FRAME_INVALID=y 390 | CONFIG_TWAI_ERRATA_FIX_RX_FIFO_CORRUPT=y 391 | # end of TWAI Configuration 392 | 393 | # 394 | # UART Configuration 395 | # 396 | # CONFIG_UART_ISR_IN_IRAM is not set 397 | # end of UART Configuration 398 | 399 | # 400 | # GPIO Configuration 401 | # 402 | # CONFIG_GPIO_ESP32_SUPPORT_SWITCH_SLP_PULL is not set 403 | # CONFIG_GPIO_CTRL_FUNC_IN_IRAM is not set 404 | # end of GPIO Configuration 405 | 406 | # 407 | # Sigma Delta Modulator Configuration 408 | # 409 | # CONFIG_SDM_CTRL_FUNC_IN_IRAM is not set 410 | # CONFIG_SDM_SUPPRESS_DEPRECATE_WARN is not set 411 | # CONFIG_SDM_ENABLE_DEBUG_LOG is not set 412 | # end of Sigma Delta Modulator Configuration 413 | 414 | # 415 | # GPTimer Configuration 416 | # 417 | # CONFIG_GPTIMER_CTRL_FUNC_IN_IRAM is not set 418 | # CONFIG_GPTIMER_ISR_IRAM_SAFE is not set 419 | # CONFIG_GPTIMER_SUPPRESS_DEPRECATE_WARN is not set 420 | # CONFIG_GPTIMER_ENABLE_DEBUG_LOG is not set 421 | # end of GPTimer Configuration 422 | 423 | # 424 | # PCNT Configuration 425 | # 426 | # CONFIG_PCNT_CTRL_FUNC_IN_IRAM is not set 427 | # CONFIG_PCNT_ISR_IRAM_SAFE is not set 428 | # CONFIG_PCNT_SUPPRESS_DEPRECATE_WARN is not set 429 | # CONFIG_PCNT_ENABLE_DEBUG_LOG is not set 430 | # end of PCNT Configuration 431 | 432 | # 433 | # RMT Configuration 434 | # 435 | # CONFIG_RMT_ISR_IRAM_SAFE is not set 436 | # CONFIG_RMT_SUPPRESS_DEPRECATE_WARN is not set 437 | # CONFIG_RMT_ENABLE_DEBUG_LOG is not set 438 | # end of RMT Configuration 439 | 440 | # 441 | # MCPWM Configuration 442 | # 443 | # CONFIG_MCPWM_ISR_IRAM_SAFE is not set 444 | # CONFIG_MCPWM_CTRL_FUNC_IN_IRAM is not set 445 | # CONFIG_MCPWM_SUPPRESS_DEPRECATE_WARN is not set 446 | # CONFIG_MCPWM_ENABLE_DEBUG_LOG is not set 447 | # end of MCPWM Configuration 448 | 449 | # 450 | # I2S Configuration 451 | # 452 | # CONFIG_I2S_ISR_IRAM_SAFE is not set 453 | # CONFIG_I2S_SUPPRESS_DEPRECATE_WARN is not set 454 | # CONFIG_I2S_ENABLE_DEBUG_LOG is not set 455 | # end of I2S Configuration 456 | # end of Driver Configurations 457 | 458 | # 459 | # eFuse Bit Manager 460 | # 461 | # CONFIG_EFUSE_CUSTOM_TABLE is not set 462 | # CONFIG_EFUSE_VIRTUAL is not set 463 | # CONFIG_EFUSE_CODE_SCHEME_COMPAT_NONE is not set 464 | CONFIG_EFUSE_CODE_SCHEME_COMPAT_3_4=y 465 | # CONFIG_EFUSE_CODE_SCHEME_COMPAT_REPEAT is not set 466 | CONFIG_EFUSE_MAX_BLK_LEN=192 467 | # end of eFuse Bit Manager 468 | 469 | # 470 | # ESP-TLS 471 | # 472 | CONFIG_ESP_TLS_USING_MBEDTLS=y 473 | # CONFIG_ESP_TLS_USE_SECURE_ELEMENT is not set 474 | # CONFIG_ESP_TLS_CLIENT_SESSION_TICKETS is not set 475 | # CONFIG_ESP_TLS_SERVER is not set 476 | # CONFIG_ESP_TLS_PSK_VERIFICATION is not set 477 | # CONFIG_ESP_TLS_INSECURE is not set 478 | # end of ESP-TLS 479 | 480 | # 481 | # ADC and ADC Calibration 482 | # 483 | # CONFIG_ADC_ONESHOT_CTRL_FUNC_IN_IRAM is not set 484 | # CONFIG_ADC_CONTINUOUS_ISR_IRAM_SAFE is not set 485 | 486 | # 487 | # ADC Calibration Configurations 488 | # 489 | CONFIG_ADC_CALI_EFUSE_TP_ENABLE=y 490 | CONFIG_ADC_CALI_EFUSE_VREF_ENABLE=y 491 | CONFIG_ADC_CALI_LUT_ENABLE=y 492 | # end of ADC Calibration Configurations 493 | 494 | CONFIG_ADC_DISABLE_DAC_OUTPUT=y 495 | # end of ADC and ADC Calibration 496 | 497 | # 498 | # Common ESP-related 499 | # 500 | CONFIG_ESP_ERR_TO_NAME_LOOKUP=y 501 | # end of Common ESP-related 502 | 503 | # 504 | # Ethernet 505 | # 506 | CONFIG_ETH_ENABLED=y 507 | CONFIG_ETH_USE_ESP32_EMAC=y 508 | CONFIG_ETH_PHY_INTERFACE_RMII=y 509 | CONFIG_ETH_RMII_CLK_INPUT=y 510 | # CONFIG_ETH_RMII_CLK_OUTPUT is not set 511 | CONFIG_ETH_RMII_CLK_IN_GPIO=0 512 | CONFIG_ETH_DMA_BUFFER_SIZE=512 513 | CONFIG_ETH_DMA_RX_BUFFER_NUM=10 514 | CONFIG_ETH_DMA_TX_BUFFER_NUM=10 515 | CONFIG_ETH_USE_SPI_ETHERNET=y 516 | # CONFIG_ETH_SPI_ETHERNET_DM9051 is not set 517 | # CONFIG_ETH_SPI_ETHERNET_W5500 is not set 518 | # CONFIG_ETH_SPI_ETHERNET_KSZ8851SNL is not set 519 | # CONFIG_ETH_USE_OPENETH is not set 520 | # CONFIG_ETH_TRANSMIT_MUTEX is not set 521 | # end of Ethernet 522 | 523 | # 524 | # Event Loop Library 525 | # 526 | # CONFIG_ESP_EVENT_LOOP_PROFILING is not set 527 | CONFIG_ESP_EVENT_POST_FROM_ISR=y 528 | CONFIG_ESP_EVENT_POST_FROM_IRAM_ISR=y 529 | # end of Event Loop Library 530 | 531 | # 532 | # GDB Stub 533 | # 534 | # end of GDB Stub 535 | 536 | # 537 | # ESP HTTP client 538 | # 539 | CONFIG_ESP_HTTP_CLIENT_ENABLE_HTTPS=y 540 | # CONFIG_ESP_HTTP_CLIENT_ENABLE_BASIC_AUTH is not set 541 | # CONFIG_ESP_HTTP_CLIENT_ENABLE_DIGEST_AUTH is not set 542 | # end of ESP HTTP client 543 | 544 | # 545 | # HTTP Server 546 | # 547 | CONFIG_HTTPD_MAX_REQ_HDR_LEN=512 548 | CONFIG_HTTPD_MAX_URI_LEN=512 549 | CONFIG_HTTPD_ERR_RESP_NO_DELAY=y 550 | CONFIG_HTTPD_PURGE_BUF_LEN=32 551 | # CONFIG_HTTPD_LOG_PURGE_DATA is not set 552 | # CONFIG_HTTPD_WS_SUPPORT is not set 553 | # CONFIG_HTTPD_QUEUE_WORK_BLOCKING is not set 554 | # end of HTTP Server 555 | 556 | # 557 | # ESP HTTPS OTA 558 | # 559 | # CONFIG_ESP_HTTPS_OTA_DECRYPT_CB is not set 560 | # CONFIG_ESP_HTTPS_OTA_ALLOW_HTTP is not set 561 | # end of ESP HTTPS OTA 562 | 563 | # 564 | # ESP HTTPS server 565 | # 566 | # CONFIG_ESP_HTTPS_SERVER_ENABLE is not set 567 | # end of ESP HTTPS server 568 | 569 | # 570 | # Hardware Settings 571 | # 572 | 573 | # 574 | # MAC Config 575 | # 576 | CONFIG_ESP_MAC_ADDR_UNIVERSE_WIFI_STA=y 577 | CONFIG_ESP_MAC_ADDR_UNIVERSE_WIFI_AP=y 578 | CONFIG_ESP_MAC_ADDR_UNIVERSE_BT=y 579 | CONFIG_ESP_MAC_ADDR_UNIVERSE_ETH=y 580 | # CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES_TWO is not set 581 | CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES_FOUR=y 582 | CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES=4 583 | # end of MAC Config 584 | 585 | # 586 | # Sleep Config 587 | # 588 | # CONFIG_ESP_SLEEP_POWER_DOWN_FLASH is not set 589 | CONFIG_ESP_SLEEP_RTC_BUS_ISO_WORKAROUND=y 590 | # CONFIG_ESP_SLEEP_GPIO_RESET_WORKAROUND is not set 591 | CONFIG_ESP_SLEEP_FLASH_LEAKAGE_WORKAROUND=y 592 | # CONFIG_ESP_SLEEP_MSPI_NEED_ALL_IO_PU is not set 593 | CONFIG_ESP_SLEEP_DEEP_SLEEP_WAKEUP_DELAY=2000 594 | # end of Sleep Config 595 | 596 | # 597 | # RTC Clock Config 598 | # 599 | CONFIG_RTC_CLK_SRC_INT_RC=y 600 | # CONFIG_RTC_CLK_SRC_EXT_CRYS is not set 601 | # CONFIG_RTC_CLK_SRC_EXT_OSC is not set 602 | # CONFIG_RTC_CLK_SRC_INT_8MD256 is not set 603 | CONFIG_RTC_CLK_CAL_CYCLES=1024 604 | # end of RTC Clock Config 605 | 606 | # 607 | # Peripheral Control 608 | # 609 | # CONFIG_PERIPH_CTRL_FUNC_IN_IRAM is not set 610 | # end of Peripheral Control 611 | 612 | # 613 | # MMU Config 614 | # 615 | CONFIG_MMU_PAGE_SIZE_64KB=y 616 | CONFIG_MMU_PAGE_MODE="64KB" 617 | CONFIG_MMU_PAGE_SIZE=0x10000 618 | # end of MMU Config 619 | 620 | CONFIG_ESP32_REV_MIN_0=y 621 | # CONFIG_ESP32_REV_MIN_1 is not set 622 | # CONFIG_ESP32_REV_MIN_2 is not set 623 | # CONFIG_ESP32_REV_MIN_3 is not set 624 | CONFIG_ESP32_REV_MIN=0 625 | 626 | # 627 | # Main XTAL Config 628 | # 629 | # CONFIG_XTAL_FREQ_26 is not set 630 | CONFIG_XTAL_FREQ_40=y 631 | # CONFIG_XTAL_FREQ_AUTO is not set 632 | CONFIG_XTAL_FREQ=40 633 | # end of Main XTAL Config 634 | # end of Hardware Settings 635 | 636 | # 637 | # LCD and Touch Panel 638 | # 639 | 640 | # 641 | # LCD Touch Drivers are maintained in the IDF Component Registry 642 | # 643 | 644 | # 645 | # LCD Peripheral Configuration 646 | # 647 | CONFIG_LCD_PANEL_IO_FORMAT_BUF_SIZE=32 648 | # CONFIG_LCD_ENABLE_DEBUG_LOG is not set 649 | # end of LCD Peripheral Configuration 650 | # end of LCD and Touch Panel 651 | 652 | # 653 | # ESP NETIF Adapter 654 | # 655 | CONFIG_ESP_NETIF_IP_LOST_TIMER_INTERVAL=120 656 | CONFIG_ESP_NETIF_TCPIP_LWIP=y 657 | # CONFIG_ESP_NETIF_LOOPBACK is not set 658 | # CONFIG_ESP_NETIF_L2_TAP is not set 659 | # CONFIG_ESP_NETIF_BRIDGE_EN is not set 660 | # end of ESP NETIF Adapter 661 | 662 | # 663 | # PHY 664 | # 665 | CONFIG_ESP_PHY_CALIBRATION_AND_DATA_STORAGE=y 666 | # CONFIG_ESP_PHY_INIT_DATA_IN_PARTITION is not set 667 | CONFIG_ESP_PHY_MAX_WIFI_TX_POWER=20 668 | CONFIG_ESP_PHY_MAX_TX_POWER=20 669 | CONFIG_ESP_PHY_REDUCE_TX_POWER=y 670 | # end of PHY 671 | 672 | # 673 | # Power Management 674 | # 675 | # CONFIG_PM_ENABLE is not set 676 | # end of Power Management 677 | 678 | # 679 | # ESP PSRAM 680 | # 681 | # CONFIG_SPIRAM is not set 682 | # end of ESP PSRAM 683 | 684 | # 685 | # ESP Ringbuf 686 | # 687 | # CONFIG_RINGBUF_PLACE_FUNCTIONS_INTO_FLASH is not set 688 | # CONFIG_RINGBUF_PLACE_ISR_FUNCTIONS_INTO_FLASH is not set 689 | # end of ESP Ringbuf 690 | 691 | # 692 | # ESP System Settings 693 | # 694 | # CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ_80 is not set 695 | CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ_160=y 696 | # CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ_240 is not set 697 | CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ=160 698 | 699 | # 700 | # Memory 701 | # 702 | # CONFIG_ESP32_USE_FIXED_STATIC_RAM_SIZE is not set 703 | # end of Memory 704 | 705 | # 706 | # Trace memory 707 | # 708 | # CONFIG_ESP32_TRAX is not set 709 | CONFIG_ESP32_TRACEMEM_RESERVE_DRAM=0x0 710 | # end of Trace memory 711 | 712 | # CONFIG_ESP_SYSTEM_PANIC_PRINT_HALT is not set 713 | CONFIG_ESP_SYSTEM_PANIC_PRINT_REBOOT=y 714 | # CONFIG_ESP_SYSTEM_PANIC_SILENT_REBOOT is not set 715 | # CONFIG_ESP_SYSTEM_PANIC_GDBSTUB is not set 716 | # CONFIG_ESP_SYSTEM_GDBSTUB_RUNTIME is not set 717 | 718 | # 719 | # Memory protection 720 | # 721 | # end of Memory protection 722 | 723 | CONFIG_ESP_SYSTEM_EVENT_QUEUE_SIZE=32 724 | CONFIG_ESP_SYSTEM_EVENT_TASK_STACK_SIZE=2304 725 | CONFIG_ESP_MAIN_TASK_STACK_SIZE=3584 726 | CONFIG_ESP_MAIN_TASK_AFFINITY_CPU0=y 727 | # CONFIG_ESP_MAIN_TASK_AFFINITY_CPU1 is not set 728 | # CONFIG_ESP_MAIN_TASK_AFFINITY_NO_AFFINITY is not set 729 | CONFIG_ESP_MAIN_TASK_AFFINITY=0x0 730 | CONFIG_ESP_MINIMAL_SHARED_STACK_SIZE=2048 731 | CONFIG_ESP_CONSOLE_UART_DEFAULT=y 732 | # CONFIG_ESP_CONSOLE_UART_CUSTOM is not set 733 | # CONFIG_ESP_CONSOLE_NONE is not set 734 | CONFIG_ESP_CONSOLE_UART=y 735 | CONFIG_ESP_CONSOLE_MULTIPLE_UART=y 736 | CONFIG_ESP_CONSOLE_UART_NUM=0 737 | CONFIG_ESP_CONSOLE_UART_BAUDRATE=115200 738 | CONFIG_ESP_INT_WDT=y 739 | CONFIG_ESP_INT_WDT_TIMEOUT_MS=300 740 | CONFIG_ESP_INT_WDT_CHECK_CPU1=y 741 | CONFIG_ESP_TASK_WDT=y 742 | # CONFIG_ESP_TASK_WDT_PANIC is not set 743 | CONFIG_ESP_TASK_WDT_TIMEOUT_S=5 744 | CONFIG_ESP_TASK_WDT_CHECK_IDLE_TASK_CPU0=y 745 | CONFIG_ESP_TASK_WDT_CHECK_IDLE_TASK_CPU1=y 746 | # CONFIG_ESP_PANIC_HANDLER_IRAM is not set 747 | # CONFIG_ESP_DEBUG_STUBS_ENABLE is not set 748 | CONFIG_ESP_DEBUG_OCDAWARE=y 749 | # CONFIG_ESP_SYSTEM_CHECK_INT_LEVEL_5 is not set 750 | CONFIG_ESP_SYSTEM_CHECK_INT_LEVEL_4=y 751 | 752 | # 753 | # Brownout Detector 754 | # 755 | CONFIG_ESP_BROWNOUT_DET=y 756 | CONFIG_ESP_BROWNOUT_DET_LVL_SEL_0=y 757 | # CONFIG_ESP_BROWNOUT_DET_LVL_SEL_1 is not set 758 | # CONFIG_ESP_BROWNOUT_DET_LVL_SEL_2 is not set 759 | # CONFIG_ESP_BROWNOUT_DET_LVL_SEL_3 is not set 760 | # CONFIG_ESP_BROWNOUT_DET_LVL_SEL_4 is not set 761 | # CONFIG_ESP_BROWNOUT_DET_LVL_SEL_5 is not set 762 | # CONFIG_ESP_BROWNOUT_DET_LVL_SEL_6 is not set 763 | # CONFIG_ESP_BROWNOUT_DET_LVL_SEL_7 is not set 764 | CONFIG_ESP_BROWNOUT_DET_LVL=0 765 | # end of Brownout Detector 766 | 767 | # CONFIG_ESP32_DISABLE_BASIC_ROM_CONSOLE is not set 768 | CONFIG_ESP_SYSTEM_BROWNOUT_INTR=y 769 | # end of ESP System Settings 770 | 771 | # 772 | # IPC (Inter-Processor Call) 773 | # 774 | CONFIG_ESP_IPC_TASK_STACK_SIZE=1024 775 | CONFIG_ESP_IPC_USES_CALLERS_PRIORITY=y 776 | CONFIG_ESP_IPC_ISR_ENABLE=y 777 | # end of IPC (Inter-Processor Call) 778 | 779 | # 780 | # High resolution timer (esp_timer) 781 | # 782 | # CONFIG_ESP_TIMER_PROFILING is not set 783 | CONFIG_ESP_TIME_FUNCS_USE_RTC_TIMER=y 784 | CONFIG_ESP_TIME_FUNCS_USE_ESP_TIMER=y 785 | CONFIG_ESP_TIMER_TASK_STACK_SIZE=3584 786 | CONFIG_ESP_TIMER_INTERRUPT_LEVEL=1 787 | # CONFIG_ESP_TIMER_SUPPORTS_ISR_DISPATCH_METHOD is not set 788 | CONFIG_ESP_TIMER_IMPL_TG0_LAC=y 789 | # end of High resolution timer (esp_timer) 790 | 791 | # 792 | # Wi-Fi 793 | # 794 | CONFIG_ESP32_WIFI_ENABLED=y 795 | CONFIG_ESP32_WIFI_STATIC_RX_BUFFER_NUM=10 796 | CONFIG_ESP32_WIFI_DYNAMIC_RX_BUFFER_NUM=32 797 | # CONFIG_ESP32_WIFI_STATIC_TX_BUFFER is not set 798 | CONFIG_ESP32_WIFI_DYNAMIC_TX_BUFFER=y 799 | CONFIG_ESP32_WIFI_TX_BUFFER_TYPE=1 800 | CONFIG_ESP32_WIFI_DYNAMIC_TX_BUFFER_NUM=32 801 | # CONFIG_ESP32_WIFI_CSI_ENABLED is not set 802 | CONFIG_ESP32_WIFI_AMPDU_TX_ENABLED=y 803 | CONFIG_ESP32_WIFI_TX_BA_WIN=6 804 | CONFIG_ESP32_WIFI_AMPDU_RX_ENABLED=y 805 | CONFIG_ESP32_WIFI_RX_BA_WIN=6 806 | CONFIG_ESP32_WIFI_NVS_ENABLED=y 807 | CONFIG_ESP32_WIFI_TASK_PINNED_TO_CORE_0=y 808 | # CONFIG_ESP32_WIFI_TASK_PINNED_TO_CORE_1 is not set 809 | CONFIG_ESP32_WIFI_SOFTAP_BEACON_MAX_LEN=752 810 | CONFIG_ESP32_WIFI_MGMT_SBUF_NUM=32 811 | CONFIG_ESP32_WIFI_IRAM_OPT=y 812 | CONFIG_ESP32_WIFI_RX_IRAM_OPT=y 813 | CONFIG_ESP32_WIFI_ENABLE_WPA3_SAE=y 814 | CONFIG_ESP32_WIFI_ENABLE_WPA3_OWE_STA=y 815 | # CONFIG_ESP_WIFI_SLP_IRAM_OPT is not set 816 | # CONFIG_ESP_WIFI_STA_DISCONNECTED_PM_ENABLE is not set 817 | # CONFIG_ESP_WIFI_GMAC_SUPPORT is not set 818 | CONFIG_ESP_WIFI_SOFTAP_SUPPORT=y 819 | # CONFIG_ESP_WIFI_SLP_BEACON_LOST_OPT is not set 820 | # end of Wi-Fi 821 | 822 | # 823 | # Core dump 824 | # 825 | # CONFIG_ESP_COREDUMP_ENABLE_TO_FLASH is not set 826 | # CONFIG_ESP_COREDUMP_ENABLE_TO_UART is not set 827 | CONFIG_ESP_COREDUMP_ENABLE_TO_NONE=y 828 | # end of Core dump 829 | 830 | # 831 | # FAT Filesystem support 832 | # 833 | CONFIG_FATFS_VOLUME_COUNT=2 834 | # CONFIG_FATFS_SECTOR_512 is not set 835 | # CONFIG_FATFS_SECTOR_1024 is not set 836 | # CONFIG_FATFS_SECTOR_2048 is not set 837 | CONFIG_FATFS_SECTOR_4096=y 838 | CONFIG_FATFS_SECTORS_PER_CLUSTER_1=y 839 | # CONFIG_FATFS_SECTORS_PER_CLUSTER_2 is not set 840 | # CONFIG_FATFS_SECTORS_PER_CLUSTER_4 is not set 841 | # CONFIG_FATFS_SECTORS_PER_CLUSTER_8 is not set 842 | # CONFIG_FATFS_SECTORS_PER_CLUSTER_16 is not set 843 | # CONFIG_FATFS_SECTORS_PER_CLUSTER_32 is not set 844 | # CONFIG_FATFS_SECTORS_PER_CLUSTER_64 is not set 845 | # CONFIG_FATFS_SECTORS_PER_CLUSTER_128 is not set 846 | # CONFIG_FATFS_CODEPAGE_DYNAMIC is not set 847 | CONFIG_FATFS_CODEPAGE_437=y 848 | # CONFIG_FATFS_CODEPAGE_720 is not set 849 | # CONFIG_FATFS_CODEPAGE_737 is not set 850 | # CONFIG_FATFS_CODEPAGE_771 is not set 851 | # CONFIG_FATFS_CODEPAGE_775 is not set 852 | # CONFIG_FATFS_CODEPAGE_850 is not set 853 | # CONFIG_FATFS_CODEPAGE_852 is not set 854 | # CONFIG_FATFS_CODEPAGE_855 is not set 855 | # CONFIG_FATFS_CODEPAGE_857 is not set 856 | # CONFIG_FATFS_CODEPAGE_860 is not set 857 | # CONFIG_FATFS_CODEPAGE_861 is not set 858 | # CONFIG_FATFS_CODEPAGE_862 is not set 859 | # CONFIG_FATFS_CODEPAGE_863 is not set 860 | # CONFIG_FATFS_CODEPAGE_864 is not set 861 | # CONFIG_FATFS_CODEPAGE_865 is not set 862 | # CONFIG_FATFS_CODEPAGE_866 is not set 863 | # CONFIG_FATFS_CODEPAGE_869 is not set 864 | # CONFIG_FATFS_CODEPAGE_932 is not set 865 | # CONFIG_FATFS_CODEPAGE_936 is not set 866 | # CONFIG_FATFS_CODEPAGE_949 is not set 867 | # CONFIG_FATFS_CODEPAGE_950 is not set 868 | CONFIG_FATFS_AUTO_TYPE=y 869 | # CONFIG_FATFS_FAT12 is not set 870 | # CONFIG_FATFS_FAT16 is not set 871 | CONFIG_FATFS_CODEPAGE=437 872 | CONFIG_FATFS_LFN_NONE=y 873 | # CONFIG_FATFS_LFN_HEAP is not set 874 | # CONFIG_FATFS_LFN_STACK is not set 875 | CONFIG_FATFS_FS_LOCK=0 876 | CONFIG_FATFS_TIMEOUT_MS=10000 877 | CONFIG_FATFS_PER_FILE_CACHE=y 878 | # CONFIG_FATFS_USE_FASTSEEK is not set 879 | # end of FAT Filesystem support 880 | 881 | # 882 | # FreeRTOS 883 | # 884 | 885 | # 886 | # Kernel 887 | # 888 | # CONFIG_FREERTOS_SMP is not set 889 | # CONFIG_FREERTOS_UNICORE is not set 890 | CONFIG_FREERTOS_HZ=100 891 | # CONFIG_FREERTOS_CHECK_STACKOVERFLOW_NONE is not set 892 | # CONFIG_FREERTOS_CHECK_STACKOVERFLOW_PTRVAL is not set 893 | CONFIG_FREERTOS_CHECK_STACKOVERFLOW_CANARY=y 894 | CONFIG_FREERTOS_THREAD_LOCAL_STORAGE_POINTERS=1 895 | CONFIG_FREERTOS_IDLE_TASK_STACKSIZE=1536 896 | # CONFIG_FREERTOS_USE_IDLE_HOOK is not set 897 | # CONFIG_FREERTOS_USE_TICK_HOOK is not set 898 | CONFIG_FREERTOS_MAX_TASK_NAME_LEN=16 899 | # CONFIG_FREERTOS_ENABLE_BACKWARD_COMPATIBILITY is not set 900 | CONFIG_FREERTOS_TIMER_TASK_PRIORITY=1 901 | CONFIG_FREERTOS_TIMER_TASK_STACK_DEPTH=2048 902 | CONFIG_FREERTOS_TIMER_QUEUE_LENGTH=10 903 | CONFIG_FREERTOS_QUEUE_REGISTRY_SIZE=0 904 | # CONFIG_FREERTOS_USE_TRACE_FACILITY is not set 905 | # CONFIG_FREERTOS_GENERATE_RUN_TIME_STATS is not set 906 | # end of Kernel 907 | 908 | # 909 | # Port 910 | # 911 | CONFIG_FREERTOS_TASK_FUNCTION_WRAPPER=y 912 | # CONFIG_FREERTOS_WATCHPOINT_END_OF_STACK is not set 913 | # CONFIG_FREERTOS_ENABLE_STATIC_TASK_CLEAN_UP is not set 914 | CONFIG_FREERTOS_CHECK_MUTEX_GIVEN_BY_OWNER=y 915 | CONFIG_FREERTOS_ISR_STACKSIZE=1536 916 | CONFIG_FREERTOS_INTERRUPT_BACKTRACE=y 917 | # CONFIG_FREERTOS_FPU_IN_ISR is not set 918 | CONFIG_FREERTOS_TICK_SUPPORT_CORETIMER=y 919 | CONFIG_FREERTOS_CORETIMER_0=y 920 | # CONFIG_FREERTOS_CORETIMER_1 is not set 921 | CONFIG_FREERTOS_SYSTICK_USES_CCOUNT=y 922 | # CONFIG_FREERTOS_PLACE_FUNCTIONS_INTO_FLASH is not set 923 | # CONFIG_FREERTOS_PLACE_SNAPSHOT_FUNS_INTO_FLASH is not set 924 | # CONFIG_FREERTOS_CHECK_PORT_CRITICAL_COMPLIANCE is not set 925 | CONFIG_FREERTOS_ASSERT_ON_UNTESTED_FUNCTION=y 926 | CONFIG_FREERTOS_ENABLE_TASK_SNAPSHOT=y 927 | # end of Port 928 | 929 | CONFIG_FREERTOS_NO_AFFINITY=0x7FFFFFFF 930 | CONFIG_FREERTOS_SUPPORT_STATIC_ALLOCATION=y 931 | CONFIG_FREERTOS_DEBUG_OCDAWARE=y 932 | # end of FreeRTOS 933 | 934 | # 935 | # Hardware Abstraction Layer (HAL) and Low Level (LL) 936 | # 937 | CONFIG_HAL_ASSERTION_EQUALS_SYSTEM=y 938 | # CONFIG_HAL_ASSERTION_DISABLE is not set 939 | # CONFIG_HAL_ASSERTION_SILENT is not set 940 | # CONFIG_HAL_ASSERTION_ENABLE is not set 941 | CONFIG_HAL_DEFAULT_ASSERTION_LEVEL=2 942 | # end of Hardware Abstraction Layer (HAL) and Low Level (LL) 943 | 944 | # 945 | # Heap memory debugging 946 | # 947 | CONFIG_HEAP_POISONING_DISABLED=y 948 | # CONFIG_HEAP_POISONING_LIGHT is not set 949 | # CONFIG_HEAP_POISONING_COMPREHENSIVE is not set 950 | CONFIG_HEAP_TRACING_OFF=y 951 | # CONFIG_HEAP_TRACING_STANDALONE is not set 952 | # CONFIG_HEAP_TRACING_TOHOST is not set 953 | # CONFIG_HEAP_ABORT_WHEN_ALLOCATION_FAILS is not set 954 | # end of Heap memory debugging 955 | 956 | # 957 | # Log output 958 | # 959 | # CONFIG_LOG_DEFAULT_LEVEL_NONE is not set 960 | # CONFIG_LOG_DEFAULT_LEVEL_ERROR is not set 961 | # CONFIG_LOG_DEFAULT_LEVEL_WARN is not set 962 | CONFIG_LOG_DEFAULT_LEVEL_INFO=y 963 | # CONFIG_LOG_DEFAULT_LEVEL_DEBUG is not set 964 | # CONFIG_LOG_DEFAULT_LEVEL_VERBOSE is not set 965 | CONFIG_LOG_DEFAULT_LEVEL=3 966 | CONFIG_LOG_MAXIMUM_EQUALS_DEFAULT=y 967 | # CONFIG_LOG_MAXIMUM_LEVEL_DEBUG is not set 968 | # CONFIG_LOG_MAXIMUM_LEVEL_VERBOSE is not set 969 | CONFIG_LOG_MAXIMUM_LEVEL=3 970 | CONFIG_LOG_COLORS=y 971 | CONFIG_LOG_TIMESTAMP_SOURCE_RTOS=y 972 | # CONFIG_LOG_TIMESTAMP_SOURCE_SYSTEM is not set 973 | # end of Log output 974 | 975 | # 976 | # LWIP 977 | # 978 | CONFIG_LWIP_LOCAL_HOSTNAME="espressif" 979 | # CONFIG_LWIP_NETIF_API is not set 980 | # CONFIG_LWIP_TCPIP_CORE_LOCKING is not set 981 | CONFIG_LWIP_DNS_SUPPORT_MDNS_QUERIES=y 982 | # CONFIG_LWIP_L2_TO_L3_COPY is not set 983 | # CONFIG_LWIP_IRAM_OPTIMIZATION is not set 984 | CONFIG_LWIP_TIMERS_ONDEMAND=y 985 | CONFIG_LWIP_MAX_SOCKETS=10 986 | # CONFIG_LWIP_USE_ONLY_LWIP_SELECT is not set 987 | # CONFIG_LWIP_SO_LINGER is not set 988 | CONFIG_LWIP_SO_REUSE=y 989 | CONFIG_LWIP_SO_REUSE_RXTOALL=y 990 | # CONFIG_LWIP_SO_RCVBUF is not set 991 | # CONFIG_LWIP_NETBUF_RECVINFO is not set 992 | CONFIG_LWIP_IP4_FRAG=y 993 | CONFIG_LWIP_IP6_FRAG=y 994 | # CONFIG_LWIP_IP4_REASSEMBLY is not set 995 | # CONFIG_LWIP_IP6_REASSEMBLY is not set 996 | # CONFIG_LWIP_IP_FORWARD is not set 997 | # CONFIG_LWIP_STATS is not set 998 | CONFIG_LWIP_ESP_GRATUITOUS_ARP=y 999 | CONFIG_LWIP_GARP_TMR_INTERVAL=60 1000 | CONFIG_LWIP_TCPIP_RECVMBOX_SIZE=32 1001 | CONFIG_LWIP_DHCP_DOES_ARP_CHECK=y 1002 | # CONFIG_LWIP_DHCP_DISABLE_CLIENT_ID is not set 1003 | CONFIG_LWIP_DHCP_DISABLE_VENDOR_CLASS_ID=y 1004 | # CONFIG_LWIP_DHCP_RESTORE_LAST_IP is not set 1005 | CONFIG_LWIP_DHCP_OPTIONS_LEN=68 1006 | CONFIG_LWIP_NUM_NETIF_CLIENT_DATA=0 1007 | 1008 | # 1009 | # DHCP server 1010 | # 1011 | CONFIG_LWIP_DHCPS=y 1012 | CONFIG_LWIP_DHCPS_LEASE_UNIT=60 1013 | CONFIG_LWIP_DHCPS_MAX_STATION_NUM=8 1014 | # end of DHCP server 1015 | 1016 | # CONFIG_LWIP_AUTOIP is not set 1017 | CONFIG_LWIP_IPV6=y 1018 | # CONFIG_LWIP_IPV6_AUTOCONFIG is not set 1019 | CONFIG_LWIP_IPV6_NUM_ADDRESSES=3 1020 | # CONFIG_LWIP_IPV6_FORWARD is not set 1021 | # CONFIG_LWIP_NETIF_STATUS_CALLBACK is not set 1022 | CONFIG_LWIP_NETIF_LOOPBACK=y 1023 | CONFIG_LWIP_LOOPBACK_MAX_PBUFS=8 1024 | 1025 | # 1026 | # TCP 1027 | # 1028 | CONFIG_LWIP_MAX_ACTIVE_TCP=16 1029 | CONFIG_LWIP_MAX_LISTENING_TCP=16 1030 | CONFIG_LWIP_TCP_HIGH_SPEED_RETRANSMISSION=y 1031 | CONFIG_LWIP_TCP_MAXRTX=12 1032 | CONFIG_LWIP_TCP_SYNMAXRTX=12 1033 | CONFIG_LWIP_TCP_MSS=1440 1034 | CONFIG_LWIP_TCP_TMR_INTERVAL=250 1035 | CONFIG_LWIP_TCP_MSL=60000 1036 | CONFIG_LWIP_TCP_FIN_WAIT_TIMEOUT=20000 1037 | CONFIG_LWIP_TCP_SND_BUF_DEFAULT=5744 1038 | CONFIG_LWIP_TCP_WND_DEFAULT=5744 1039 | CONFIG_LWIP_TCP_RECVMBOX_SIZE=6 1040 | CONFIG_LWIP_TCP_QUEUE_OOSEQ=y 1041 | # CONFIG_LWIP_TCP_SACK_OUT is not set 1042 | CONFIG_LWIP_TCP_OVERSIZE_MSS=y 1043 | # CONFIG_LWIP_TCP_OVERSIZE_QUARTER_MSS is not set 1044 | # CONFIG_LWIP_TCP_OVERSIZE_DISABLE is not set 1045 | CONFIG_LWIP_TCP_RTO_TIME=1500 1046 | # end of TCP 1047 | 1048 | # 1049 | # UDP 1050 | # 1051 | CONFIG_LWIP_MAX_UDP_PCBS=16 1052 | CONFIG_LWIP_UDP_RECVMBOX_SIZE=6 1053 | # end of UDP 1054 | 1055 | # 1056 | # Checksums 1057 | # 1058 | # CONFIG_LWIP_CHECKSUM_CHECK_IP is not set 1059 | # CONFIG_LWIP_CHECKSUM_CHECK_UDP is not set 1060 | CONFIG_LWIP_CHECKSUM_CHECK_ICMP=y 1061 | # end of Checksums 1062 | 1063 | CONFIG_LWIP_TCPIP_TASK_STACK_SIZE=3072 1064 | CONFIG_LWIP_TCPIP_TASK_AFFINITY_NO_AFFINITY=y 1065 | # CONFIG_LWIP_TCPIP_TASK_AFFINITY_CPU0 is not set 1066 | # CONFIG_LWIP_TCPIP_TASK_AFFINITY_CPU1 is not set 1067 | CONFIG_LWIP_TCPIP_TASK_AFFINITY=0x7FFFFFFF 1068 | # CONFIG_LWIP_PPP_SUPPORT is not set 1069 | CONFIG_LWIP_IPV6_MEMP_NUM_ND6_QUEUE=3 1070 | CONFIG_LWIP_IPV6_ND6_NUM_NEIGHBORS=5 1071 | # CONFIG_LWIP_SLIP_SUPPORT is not set 1072 | 1073 | # 1074 | # ICMP 1075 | # 1076 | CONFIG_LWIP_ICMP=y 1077 | # CONFIG_LWIP_MULTICAST_PING is not set 1078 | # CONFIG_LWIP_BROADCAST_PING is not set 1079 | # end of ICMP 1080 | 1081 | # 1082 | # LWIP RAW API 1083 | # 1084 | CONFIG_LWIP_MAX_RAW_PCBS=16 1085 | # end of LWIP RAW API 1086 | 1087 | # 1088 | # SNTP 1089 | # 1090 | CONFIG_LWIP_SNTP_MAX_SERVERS=1 1091 | # CONFIG_LWIP_DHCP_GET_NTP_SRV is not set 1092 | CONFIG_LWIP_SNTP_UPDATE_DELAY=3600000 1093 | # end of SNTP 1094 | 1095 | CONFIG_LWIP_BRIDGEIF_MAX_PORTS=7 1096 | CONFIG_LWIP_ESP_LWIP_ASSERT=y 1097 | 1098 | # 1099 | # Hooks 1100 | # 1101 | # CONFIG_LWIP_HOOK_TCP_ISN_NONE is not set 1102 | CONFIG_LWIP_HOOK_TCP_ISN_DEFAULT=y 1103 | # CONFIG_LWIP_HOOK_TCP_ISN_CUSTOM is not set 1104 | CONFIG_LWIP_HOOK_IP6_ROUTE_NONE=y 1105 | # CONFIG_LWIP_HOOK_IP6_ROUTE_DEFAULT is not set 1106 | # CONFIG_LWIP_HOOK_IP6_ROUTE_CUSTOM is not set 1107 | CONFIG_LWIP_HOOK_ND6_GET_GW_NONE=y 1108 | # CONFIG_LWIP_HOOK_ND6_GET_GW_DEFAULT is not set 1109 | # CONFIG_LWIP_HOOK_ND6_GET_GW_CUSTOM is not set 1110 | CONFIG_LWIP_HOOK_NETCONN_EXT_RESOLVE_NONE=y 1111 | # CONFIG_LWIP_HOOK_NETCONN_EXT_RESOLVE_DEFAULT is not set 1112 | # CONFIG_LWIP_HOOK_NETCONN_EXT_RESOLVE_CUSTOM is not set 1113 | CONFIG_LWIP_HOOK_IP6_INPUT_NONE=y 1114 | # CONFIG_LWIP_HOOK_IP6_INPUT_DEFAULT is not set 1115 | # CONFIG_LWIP_HOOK_IP6_INPUT_CUSTOM is not set 1116 | # end of Hooks 1117 | 1118 | # CONFIG_LWIP_DEBUG is not set 1119 | # end of LWIP 1120 | 1121 | # 1122 | # mbedTLS 1123 | # 1124 | CONFIG_MBEDTLS_INTERNAL_MEM_ALLOC=y 1125 | # CONFIG_MBEDTLS_DEFAULT_MEM_ALLOC is not set 1126 | # CONFIG_MBEDTLS_CUSTOM_MEM_ALLOC is not set 1127 | CONFIG_MBEDTLS_ASYMMETRIC_CONTENT_LEN=y 1128 | CONFIG_MBEDTLS_SSL_IN_CONTENT_LEN=16384 1129 | CONFIG_MBEDTLS_SSL_OUT_CONTENT_LEN=4096 1130 | # CONFIG_MBEDTLS_DYNAMIC_BUFFER is not set 1131 | # CONFIG_MBEDTLS_DEBUG is not set 1132 | 1133 | # 1134 | # mbedTLS v3.x related 1135 | # 1136 | # CONFIG_MBEDTLS_SSL_PROTO_TLS1_3 is not set 1137 | # CONFIG_MBEDTLS_SSL_VARIABLE_BUFFER_LENGTH is not set 1138 | # CONFIG_MBEDTLS_X509_TRUSTED_CERT_CALLBACK is not set 1139 | # CONFIG_MBEDTLS_SSL_CONTEXT_SERIALIZATION is not set 1140 | CONFIG_MBEDTLS_SSL_KEEP_PEER_CERTIFICATE=y 1141 | # end of mbedTLS v3.x related 1142 | 1143 | # 1144 | # Certificate Bundle 1145 | # 1146 | CONFIG_MBEDTLS_CERTIFICATE_BUNDLE=y 1147 | CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_FULL=y 1148 | # CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_CMN is not set 1149 | # CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_NONE is not set 1150 | # CONFIG_MBEDTLS_CUSTOM_CERTIFICATE_BUNDLE is not set 1151 | CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_MAX_CERTS=200 1152 | # end of Certificate Bundle 1153 | 1154 | # CONFIG_MBEDTLS_ECP_RESTARTABLE is not set 1155 | # CONFIG_MBEDTLS_CMAC_C is not set 1156 | CONFIG_MBEDTLS_HARDWARE_AES=y 1157 | CONFIG_MBEDTLS_HARDWARE_MPI=y 1158 | CONFIG_MBEDTLS_HARDWARE_SHA=y 1159 | CONFIG_MBEDTLS_ROM_MD5=y 1160 | # CONFIG_MBEDTLS_ATCA_HW_ECDSA_SIGN is not set 1161 | # CONFIG_MBEDTLS_ATCA_HW_ECDSA_VERIFY is not set 1162 | CONFIG_MBEDTLS_HAVE_TIME=y 1163 | # CONFIG_MBEDTLS_PLATFORM_TIME_ALT is not set 1164 | # CONFIG_MBEDTLS_HAVE_TIME_DATE is not set 1165 | CONFIG_MBEDTLS_ECDSA_DETERMINISTIC=y 1166 | CONFIG_MBEDTLS_SHA512_C=y 1167 | CONFIG_MBEDTLS_TLS_SERVER_AND_CLIENT=y 1168 | # CONFIG_MBEDTLS_TLS_SERVER_ONLY is not set 1169 | # CONFIG_MBEDTLS_TLS_CLIENT_ONLY is not set 1170 | # CONFIG_MBEDTLS_TLS_DISABLED is not set 1171 | CONFIG_MBEDTLS_TLS_SERVER=y 1172 | CONFIG_MBEDTLS_TLS_CLIENT=y 1173 | CONFIG_MBEDTLS_TLS_ENABLED=y 1174 | 1175 | # 1176 | # TLS Key Exchange Methods 1177 | # 1178 | # CONFIG_MBEDTLS_PSK_MODES is not set 1179 | CONFIG_MBEDTLS_KEY_EXCHANGE_RSA=y 1180 | CONFIG_MBEDTLS_KEY_EXCHANGE_ELLIPTIC_CURVE=y 1181 | CONFIG_MBEDTLS_KEY_EXCHANGE_ECDHE_RSA=y 1182 | CONFIG_MBEDTLS_KEY_EXCHANGE_ECDHE_ECDSA=y 1183 | CONFIG_MBEDTLS_KEY_EXCHANGE_ECDH_ECDSA=y 1184 | CONFIG_MBEDTLS_KEY_EXCHANGE_ECDH_RSA=y 1185 | # end of TLS Key Exchange Methods 1186 | 1187 | CONFIG_MBEDTLS_SSL_RENEGOTIATION=y 1188 | CONFIG_MBEDTLS_SSL_PROTO_TLS1_2=y 1189 | # CONFIG_MBEDTLS_SSL_PROTO_GMTSSL1_1 is not set 1190 | # CONFIG_MBEDTLS_SSL_PROTO_DTLS is not set 1191 | CONFIG_MBEDTLS_SSL_ALPN=y 1192 | CONFIG_MBEDTLS_CLIENT_SSL_SESSION_TICKETS=y 1193 | CONFIG_MBEDTLS_SERVER_SSL_SESSION_TICKETS=y 1194 | 1195 | # 1196 | # Symmetric Ciphers 1197 | # 1198 | CONFIG_MBEDTLS_AES_C=y 1199 | # CONFIG_MBEDTLS_CAMELLIA_C is not set 1200 | # CONFIG_MBEDTLS_DES_C is not set 1201 | # CONFIG_MBEDTLS_BLOWFISH_C is not set 1202 | # CONFIG_MBEDTLS_XTEA_C is not set 1203 | CONFIG_MBEDTLS_CCM_C=y 1204 | CONFIG_MBEDTLS_GCM_C=y 1205 | # CONFIG_MBEDTLS_NIST_KW_C is not set 1206 | # end of Symmetric Ciphers 1207 | 1208 | # CONFIG_MBEDTLS_RIPEMD160_C is not set 1209 | 1210 | # 1211 | # Certificates 1212 | # 1213 | CONFIG_MBEDTLS_PEM_PARSE_C=y 1214 | CONFIG_MBEDTLS_PEM_WRITE_C=y 1215 | CONFIG_MBEDTLS_X509_CRL_PARSE_C=y 1216 | CONFIG_MBEDTLS_X509_CSR_PARSE_C=y 1217 | # end of Certificates 1218 | 1219 | CONFIG_MBEDTLS_ECP_C=y 1220 | # CONFIG_MBEDTLS_DHM_C is not set 1221 | CONFIG_MBEDTLS_ECDH_C=y 1222 | CONFIG_MBEDTLS_ECDSA_C=y 1223 | # CONFIG_MBEDTLS_ECJPAKE_C is not set 1224 | CONFIG_MBEDTLS_ECP_DP_SECP192R1_ENABLED=y 1225 | CONFIG_MBEDTLS_ECP_DP_SECP224R1_ENABLED=y 1226 | CONFIG_MBEDTLS_ECP_DP_SECP256R1_ENABLED=y 1227 | CONFIG_MBEDTLS_ECP_DP_SECP384R1_ENABLED=y 1228 | CONFIG_MBEDTLS_ECP_DP_SECP521R1_ENABLED=y 1229 | CONFIG_MBEDTLS_ECP_DP_SECP192K1_ENABLED=y 1230 | CONFIG_MBEDTLS_ECP_DP_SECP224K1_ENABLED=y 1231 | CONFIG_MBEDTLS_ECP_DP_SECP256K1_ENABLED=y 1232 | CONFIG_MBEDTLS_ECP_DP_BP256R1_ENABLED=y 1233 | CONFIG_MBEDTLS_ECP_DP_BP384R1_ENABLED=y 1234 | CONFIG_MBEDTLS_ECP_DP_BP512R1_ENABLED=y 1235 | CONFIG_MBEDTLS_ECP_DP_CURVE25519_ENABLED=y 1236 | CONFIG_MBEDTLS_ECP_NIST_OPTIM=y 1237 | # CONFIG_MBEDTLS_POLY1305_C is not set 1238 | # CONFIG_MBEDTLS_CHACHA20_C is not set 1239 | # CONFIG_MBEDTLS_HKDF_C is not set 1240 | # CONFIG_MBEDTLS_THREADING_C is not set 1241 | # CONFIG_MBEDTLS_LARGE_KEY_SOFTWARE_MPI is not set 1242 | # CONFIG_MBEDTLS_SECURITY_RISKS is not set 1243 | # end of mbedTLS 1244 | 1245 | # 1246 | # ESP-MQTT Configurations 1247 | # 1248 | CONFIG_MQTT_PROTOCOL_311=y 1249 | # CONFIG_MQTT_PROTOCOL_5 is not set 1250 | CONFIG_MQTT_TRANSPORT_SSL=y 1251 | CONFIG_MQTT_TRANSPORT_WEBSOCKET=y 1252 | CONFIG_MQTT_TRANSPORT_WEBSOCKET_SECURE=y 1253 | # CONFIG_MQTT_MSG_ID_INCREMENTAL is not set 1254 | # CONFIG_MQTT_SKIP_PUBLISH_IF_DISCONNECTED is not set 1255 | # CONFIG_MQTT_REPORT_DELETED_MESSAGES is not set 1256 | # CONFIG_MQTT_USE_CUSTOM_CONFIG is not set 1257 | # CONFIG_MQTT_TASK_CORE_SELECTION_ENABLED is not set 1258 | # CONFIG_MQTT_CUSTOM_OUTBOX is not set 1259 | # end of ESP-MQTT Configurations 1260 | 1261 | # 1262 | # Newlib 1263 | # 1264 | CONFIG_NEWLIB_STDOUT_LINE_ENDING_CRLF=y 1265 | # CONFIG_NEWLIB_STDOUT_LINE_ENDING_LF is not set 1266 | # CONFIG_NEWLIB_STDOUT_LINE_ENDING_CR is not set 1267 | # CONFIG_NEWLIB_STDIN_LINE_ENDING_CRLF is not set 1268 | # CONFIG_NEWLIB_STDIN_LINE_ENDING_LF is not set 1269 | CONFIG_NEWLIB_STDIN_LINE_ENDING_CR=y 1270 | # CONFIG_NEWLIB_NANO_FORMAT is not set 1271 | CONFIG_NEWLIB_TIME_SYSCALL_USE_RTC_HRT=y 1272 | # CONFIG_NEWLIB_TIME_SYSCALL_USE_RTC is not set 1273 | # CONFIG_NEWLIB_TIME_SYSCALL_USE_HRT is not set 1274 | # CONFIG_NEWLIB_TIME_SYSCALL_USE_NONE is not set 1275 | # end of Newlib 1276 | 1277 | # 1278 | # NVS 1279 | # 1280 | # CONFIG_NVS_ASSERT_ERROR_CHECK is not set 1281 | # end of NVS 1282 | 1283 | # 1284 | # OpenThread 1285 | # 1286 | # CONFIG_OPENTHREAD_ENABLED is not set 1287 | # end of OpenThread 1288 | 1289 | # 1290 | # Protocomm 1291 | # 1292 | CONFIG_ESP_PROTOCOMM_SUPPORT_SECURITY_VERSION_0=y 1293 | CONFIG_ESP_PROTOCOMM_SUPPORT_SECURITY_VERSION_1=y 1294 | CONFIG_ESP_PROTOCOMM_SUPPORT_SECURITY_VERSION_2=y 1295 | # end of Protocomm 1296 | 1297 | # 1298 | # PThreads 1299 | # 1300 | CONFIG_PTHREAD_TASK_PRIO_DEFAULT=5 1301 | CONFIG_PTHREAD_TASK_STACK_SIZE_DEFAULT=3072 1302 | CONFIG_PTHREAD_STACK_MIN=768 1303 | CONFIG_PTHREAD_DEFAULT_CORE_NO_AFFINITY=y 1304 | # CONFIG_PTHREAD_DEFAULT_CORE_0 is not set 1305 | # CONFIG_PTHREAD_DEFAULT_CORE_1 is not set 1306 | CONFIG_PTHREAD_TASK_CORE_DEFAULT=-1 1307 | CONFIG_PTHREAD_TASK_NAME_DEFAULT="pthread" 1308 | # end of PThreads 1309 | 1310 | # 1311 | # SPI Flash driver 1312 | # 1313 | # CONFIG_SPI_FLASH_VERIFY_WRITE is not set 1314 | # CONFIG_SPI_FLASH_ENABLE_COUNTERS is not set 1315 | CONFIG_SPI_FLASH_ROM_DRIVER_PATCH=y 1316 | CONFIG_SPI_FLASH_DANGEROUS_WRITE_ABORTS=y 1317 | # CONFIG_SPI_FLASH_DANGEROUS_WRITE_FAILS is not set 1318 | # CONFIG_SPI_FLASH_DANGEROUS_WRITE_ALLOWED is not set 1319 | # CONFIG_SPI_FLASH_SHARE_SPI1_BUS is not set 1320 | # CONFIG_SPI_FLASH_BYPASS_BLOCK_ERASE is not set 1321 | CONFIG_SPI_FLASH_YIELD_DURING_ERASE=y 1322 | CONFIG_SPI_FLASH_ERASE_YIELD_DURATION_MS=20 1323 | CONFIG_SPI_FLASH_ERASE_YIELD_TICKS=1 1324 | CONFIG_SPI_FLASH_WRITE_CHUNK_SIZE=8192 1325 | # CONFIG_SPI_FLASH_SIZE_OVERRIDE is not set 1326 | # CONFIG_SPI_FLASH_CHECK_ERASE_TIMEOUT_DISABLED is not set 1327 | # CONFIG_SPI_FLASH_OVERRIDE_CHIP_DRIVER_LIST is not set 1328 | 1329 | # 1330 | # SPI Flash behavior when brownout 1331 | # 1332 | CONFIG_SPI_FLASH_BROWNOUT_RESET_XMC=y 1333 | CONFIG_SPI_FLASH_BROWNOUT_RESET=y 1334 | # end of SPI Flash behavior when brownout 1335 | 1336 | # 1337 | # Auto-detect flash chips 1338 | # 1339 | CONFIG_SPI_FLASH_SUPPORT_ISSI_CHIP=y 1340 | CONFIG_SPI_FLASH_SUPPORT_MXIC_CHIP=y 1341 | CONFIG_SPI_FLASH_SUPPORT_GD_CHIP=y 1342 | CONFIG_SPI_FLASH_SUPPORT_WINBOND_CHIP=y 1343 | # CONFIG_SPI_FLASH_SUPPORT_BOYA_CHIP is not set 1344 | # CONFIG_SPI_FLASH_SUPPORT_TH_CHIP is not set 1345 | # end of Auto-detect flash chips 1346 | 1347 | CONFIG_SPI_FLASH_ENABLE_ENCRYPTED_READ_WRITE=y 1348 | # end of SPI Flash driver 1349 | 1350 | # 1351 | # SPIFFS Configuration 1352 | # 1353 | CONFIG_SPIFFS_MAX_PARTITIONS=3 1354 | 1355 | # 1356 | # SPIFFS Cache Configuration 1357 | # 1358 | CONFIG_SPIFFS_CACHE=y 1359 | CONFIG_SPIFFS_CACHE_WR=y 1360 | # CONFIG_SPIFFS_CACHE_STATS is not set 1361 | # end of SPIFFS Cache Configuration 1362 | 1363 | CONFIG_SPIFFS_PAGE_CHECK=y 1364 | CONFIG_SPIFFS_GC_MAX_RUNS=10 1365 | # CONFIG_SPIFFS_GC_STATS is not set 1366 | CONFIG_SPIFFS_PAGE_SIZE=256 1367 | CONFIG_SPIFFS_OBJ_NAME_LEN=32 1368 | # CONFIG_SPIFFS_FOLLOW_SYMLINKS is not set 1369 | CONFIG_SPIFFS_USE_MAGIC=y 1370 | CONFIG_SPIFFS_USE_MAGIC_LENGTH=y 1371 | CONFIG_SPIFFS_META_LENGTH=4 1372 | CONFIG_SPIFFS_USE_MTIME=y 1373 | 1374 | # 1375 | # Debug Configuration 1376 | # 1377 | # CONFIG_SPIFFS_DBG is not set 1378 | # CONFIG_SPIFFS_API_DBG is not set 1379 | # CONFIG_SPIFFS_GC_DBG is not set 1380 | # CONFIG_SPIFFS_CACHE_DBG is not set 1381 | # CONFIG_SPIFFS_CHECK_DBG is not set 1382 | # CONFIG_SPIFFS_TEST_VISUALISATION is not set 1383 | # end of Debug Configuration 1384 | # end of SPIFFS Configuration 1385 | 1386 | # 1387 | # TCP Transport 1388 | # 1389 | 1390 | # 1391 | # Websocket 1392 | # 1393 | CONFIG_WS_TRANSPORT=y 1394 | CONFIG_WS_BUFFER_SIZE=1024 1395 | # CONFIG_WS_DYNAMIC_BUFFER is not set 1396 | # end of Websocket 1397 | # end of TCP Transport 1398 | 1399 | # 1400 | # Ultra Low Power (ULP) Co-processor 1401 | # 1402 | # CONFIG_ULP_COPROC_ENABLED is not set 1403 | # end of Ultra Low Power (ULP) Co-processor 1404 | 1405 | # 1406 | # Unity unit testing library 1407 | # 1408 | CONFIG_UNITY_ENABLE_FLOAT=y 1409 | CONFIG_UNITY_ENABLE_DOUBLE=y 1410 | # CONFIG_UNITY_ENABLE_64BIT is not set 1411 | # CONFIG_UNITY_ENABLE_COLOR is not set 1412 | CONFIG_UNITY_ENABLE_IDF_TEST_RUNNER=y 1413 | # CONFIG_UNITY_ENABLE_FIXTURE is not set 1414 | # CONFIG_UNITY_ENABLE_BACKTRACE_ON_FAIL is not set 1415 | # end of Unity unit testing library 1416 | 1417 | # 1418 | # Virtual file system 1419 | # 1420 | CONFIG_VFS_SUPPORT_IO=y 1421 | CONFIG_VFS_SUPPORT_DIR=y 1422 | CONFIG_VFS_SUPPORT_SELECT=y 1423 | CONFIG_VFS_SUPPRESS_SELECT_DEBUG_OUTPUT=y 1424 | CONFIG_VFS_SUPPORT_TERMIOS=y 1425 | 1426 | # 1427 | # Host File System I/O (Semihosting) 1428 | # 1429 | CONFIG_VFS_SEMIHOSTFS_MAX_MOUNT_POINTS=1 1430 | # end of Host File System I/O (Semihosting) 1431 | # end of Virtual file system 1432 | 1433 | # 1434 | # Wear Levelling 1435 | # 1436 | # CONFIG_WL_SECTOR_SIZE_512 is not set 1437 | CONFIG_WL_SECTOR_SIZE_4096=y 1438 | CONFIG_WL_SECTOR_SIZE=4096 1439 | # end of Wear Levelling 1440 | 1441 | # 1442 | # Wi-Fi Provisioning Manager 1443 | # 1444 | CONFIG_WIFI_PROV_SCAN_MAX_ENTRIES=16 1445 | CONFIG_WIFI_PROV_AUTOSTOP_TIMEOUT=30 1446 | CONFIG_WIFI_PROV_BLE_FORCE_ENCRYPTION=y 1447 | # end of Wi-Fi Provisioning Manager 1448 | 1449 | # 1450 | # Supplicant 1451 | # 1452 | CONFIG_WPA_MBEDTLS_CRYPTO=y 1453 | CONFIG_WPA_MBEDTLS_TLS_CLIENT=y 1454 | # CONFIG_WPA_WAPI_PSK is not set 1455 | # CONFIG_WPA_SUITE_B_192 is not set 1456 | # CONFIG_WPA_DEBUG_PRINT is not set 1457 | # CONFIG_WPA_TESTING_OPTIONS is not set 1458 | # CONFIG_WPA_WPS_STRICT is not set 1459 | # CONFIG_WPA_11KV_SUPPORT is not set 1460 | # CONFIG_WPA_MBO_SUPPORT is not set 1461 | # CONFIG_WPA_DPP_SUPPORT is not set 1462 | # CONFIG_WPA_11R_SUPPORT is not set 1463 | # CONFIG_WPA_WPS_SOFTAP_REGISTRAR is not set 1464 | # end of Supplicant 1465 | # end of Component config 1466 | 1467 | # Deprecated options for backward compatibility 1468 | # CONFIG_NO_BLOBS is not set 1469 | # CONFIG_ESP32_NO_BLOBS is not set 1470 | # CONFIG_ESP32_COMPATIBLE_PRE_V2_1_BOOTLOADERS is not set 1471 | # CONFIG_ESP32_COMPATIBLE_PRE_V3_1_BOOTLOADERS is not set 1472 | # CONFIG_LOG_BOOTLOADER_LEVEL_NONE is not set 1473 | # CONFIG_LOG_BOOTLOADER_LEVEL_ERROR is not set 1474 | # CONFIG_LOG_BOOTLOADER_LEVEL_WARN is not set 1475 | CONFIG_LOG_BOOTLOADER_LEVEL_INFO=y 1476 | # CONFIG_LOG_BOOTLOADER_LEVEL_DEBUG is not set 1477 | # CONFIG_LOG_BOOTLOADER_LEVEL_VERBOSE is not set 1478 | CONFIG_LOG_BOOTLOADER_LEVEL=3 1479 | # CONFIG_APP_ROLLBACK_ENABLE is not set 1480 | # CONFIG_FLASH_ENCRYPTION_ENABLED is not set 1481 | # CONFIG_FLASHMODE_QIO is not set 1482 | # CONFIG_FLASHMODE_QOUT is not set 1483 | CONFIG_FLASHMODE_DIO=y 1484 | # CONFIG_FLASHMODE_DOUT is not set 1485 | CONFIG_MONITOR_BAUD=115200 1486 | CONFIG_OPTIMIZATION_LEVEL_DEBUG=y 1487 | CONFIG_COMPILER_OPTIMIZATION_LEVEL_DEBUG=y 1488 | # CONFIG_OPTIMIZATION_LEVEL_RELEASE is not set 1489 | # CONFIG_COMPILER_OPTIMIZATION_LEVEL_RELEASE is not set 1490 | CONFIG_OPTIMIZATION_ASSERTIONS_ENABLED=y 1491 | # CONFIG_OPTIMIZATION_ASSERTIONS_SILENT is not set 1492 | # CONFIG_OPTIMIZATION_ASSERTIONS_DISABLED is not set 1493 | CONFIG_OPTIMIZATION_ASSERTION_LEVEL=2 1494 | # CONFIG_CXX_EXCEPTIONS is not set 1495 | CONFIG_STACK_CHECK_NONE=y 1496 | # CONFIG_STACK_CHECK_NORM is not set 1497 | # CONFIG_STACK_CHECK_STRONG is not set 1498 | # CONFIG_STACK_CHECK_ALL is not set 1499 | # CONFIG_WARN_WRITE_STRINGS is not set 1500 | # CONFIG_ESP32_APPTRACE_DEST_TRAX is not set 1501 | CONFIG_ESP32_APPTRACE_DEST_NONE=y 1502 | CONFIG_ESP32_APPTRACE_LOCK_ENABLE=y 1503 | CONFIG_ADC2_DISABLE_DAC=y 1504 | # CONFIG_MCPWM_ISR_IN_IRAM is not set 1505 | # CONFIG_EVENT_LOOP_PROFILING is not set 1506 | CONFIG_POST_EVENTS_FROM_ISR=y 1507 | CONFIG_POST_EVENTS_FROM_IRAM_ISR=y 1508 | # CONFIG_OTA_ALLOW_HTTP is not set 1509 | # CONFIG_TWO_UNIVERSAL_MAC_ADDRESS is not set 1510 | CONFIG_FOUR_UNIVERSAL_MAC_ADDRESS=y 1511 | CONFIG_NUMBER_OF_UNIVERSAL_MAC_ADDRESS=4 1512 | # CONFIG_ESP_SYSTEM_PD_FLASH is not set 1513 | CONFIG_ESP32_DEEP_SLEEP_WAKEUP_DELAY=2000 1514 | CONFIG_ESP32_RTC_CLK_SRC_INT_RC=y 1515 | CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_RC=y 1516 | # CONFIG_ESP32_RTC_CLK_SRC_EXT_CRYS is not set 1517 | # CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_CRYSTAL is not set 1518 | # CONFIG_ESP32_RTC_CLK_SRC_EXT_OSC is not set 1519 | # CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_OSC is not set 1520 | # CONFIG_ESP32_RTC_CLK_SRC_INT_8MD256 is not set 1521 | # CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_8MD256 is not set 1522 | CONFIG_ESP32_RTC_CLK_CAL_CYCLES=1024 1523 | # CONFIG_ESP32_XTAL_FREQ_26 is not set 1524 | CONFIG_ESP32_XTAL_FREQ_40=y 1525 | # CONFIG_ESP32_XTAL_FREQ_AUTO is not set 1526 | CONFIG_ESP32_XTAL_FREQ=40 1527 | CONFIG_ESP32_PHY_CALIBRATION_AND_DATA_STORAGE=y 1528 | # CONFIG_ESP32_PHY_INIT_DATA_IN_PARTITION is not set 1529 | CONFIG_ESP32_PHY_MAX_WIFI_TX_POWER=20 1530 | CONFIG_ESP32_PHY_MAX_TX_POWER=20 1531 | CONFIG_REDUCE_PHY_TX_POWER=y 1532 | CONFIG_ESP32_REDUCE_PHY_TX_POWER=y 1533 | # CONFIG_SPIRAM_SUPPORT is not set 1534 | # CONFIG_ESP32_SPIRAM_SUPPORT is not set 1535 | # CONFIG_ESP32_DEFAULT_CPU_FREQ_80 is not set 1536 | CONFIG_ESP32_DEFAULT_CPU_FREQ_160=y 1537 | # CONFIG_ESP32_DEFAULT_CPU_FREQ_240 is not set 1538 | CONFIG_ESP32_DEFAULT_CPU_FREQ_MHZ=160 1539 | CONFIG_TRACEMEM_RESERVE_DRAM=0x0 1540 | # CONFIG_ESP32_PANIC_PRINT_HALT is not set 1541 | CONFIG_ESP32_PANIC_PRINT_REBOOT=y 1542 | # CONFIG_ESP32_PANIC_SILENT_REBOOT is not set 1543 | # CONFIG_ESP32_PANIC_GDBSTUB is not set 1544 | CONFIG_SYSTEM_EVENT_QUEUE_SIZE=32 1545 | CONFIG_SYSTEM_EVENT_TASK_STACK_SIZE=2304 1546 | CONFIG_MAIN_TASK_STACK_SIZE=3584 1547 | CONFIG_CONSOLE_UART_DEFAULT=y 1548 | # CONFIG_CONSOLE_UART_CUSTOM is not set 1549 | # CONFIG_CONSOLE_UART_NONE is not set 1550 | # CONFIG_ESP_CONSOLE_UART_NONE is not set 1551 | CONFIG_CONSOLE_UART=y 1552 | CONFIG_CONSOLE_UART_NUM=0 1553 | CONFIG_CONSOLE_UART_BAUDRATE=115200 1554 | CONFIG_INT_WDT=y 1555 | CONFIG_INT_WDT_TIMEOUT_MS=300 1556 | CONFIG_INT_WDT_CHECK_CPU1=y 1557 | CONFIG_TASK_WDT=y 1558 | # CONFIG_TASK_WDT_PANIC is not set 1559 | CONFIG_TASK_WDT_TIMEOUT_S=5 1560 | CONFIG_TASK_WDT_CHECK_IDLE_TASK_CPU0=y 1561 | CONFIG_TASK_WDT_CHECK_IDLE_TASK_CPU1=y 1562 | # CONFIG_ESP32_DEBUG_STUBS_ENABLE is not set 1563 | CONFIG_ESP32_DEBUG_OCDAWARE=y 1564 | CONFIG_BROWNOUT_DET=y 1565 | CONFIG_ESP32_BROWNOUT_DET=y 1566 | CONFIG_BROWNOUT_DET_LVL_SEL_0=y 1567 | CONFIG_ESP32_BROWNOUT_DET_LVL_SEL_0=y 1568 | # CONFIG_BROWNOUT_DET_LVL_SEL_1 is not set 1569 | # CONFIG_ESP32_BROWNOUT_DET_LVL_SEL_1 is not set 1570 | # CONFIG_BROWNOUT_DET_LVL_SEL_2 is not set 1571 | # CONFIG_ESP32_BROWNOUT_DET_LVL_SEL_2 is not set 1572 | # CONFIG_BROWNOUT_DET_LVL_SEL_3 is not set 1573 | # CONFIG_ESP32_BROWNOUT_DET_LVL_SEL_3 is not set 1574 | # CONFIG_BROWNOUT_DET_LVL_SEL_4 is not set 1575 | # CONFIG_ESP32_BROWNOUT_DET_LVL_SEL_4 is not set 1576 | # CONFIG_BROWNOUT_DET_LVL_SEL_5 is not set 1577 | # CONFIG_ESP32_BROWNOUT_DET_LVL_SEL_5 is not set 1578 | # CONFIG_BROWNOUT_DET_LVL_SEL_6 is not set 1579 | # CONFIG_ESP32_BROWNOUT_DET_LVL_SEL_6 is not set 1580 | # CONFIG_BROWNOUT_DET_LVL_SEL_7 is not set 1581 | # CONFIG_ESP32_BROWNOUT_DET_LVL_SEL_7 is not set 1582 | CONFIG_BROWNOUT_DET_LVL=0 1583 | CONFIG_ESP32_BROWNOUT_DET_LVL=0 1584 | # CONFIG_DISABLE_BASIC_ROM_CONSOLE is not set 1585 | CONFIG_IPC_TASK_STACK_SIZE=1024 1586 | CONFIG_TIMER_TASK_STACK_SIZE=3584 1587 | # CONFIG_ESP32_ENABLE_COREDUMP_TO_FLASH is not set 1588 | # CONFIG_ESP32_ENABLE_COREDUMP_TO_UART is not set 1589 | CONFIG_ESP32_ENABLE_COREDUMP_TO_NONE=y 1590 | CONFIG_TIMER_TASK_PRIORITY=1 1591 | CONFIG_TIMER_TASK_STACK_DEPTH=2048 1592 | CONFIG_TIMER_QUEUE_LENGTH=10 1593 | # CONFIG_ENABLE_STATIC_TASK_CLEAN_UP_HOOK is not set 1594 | # CONFIG_HAL_ASSERTION_SILIENT is not set 1595 | # CONFIG_L2_TO_L3_COPY is not set 1596 | CONFIG_ESP_GRATUITOUS_ARP=y 1597 | CONFIG_GARP_TMR_INTERVAL=60 1598 | CONFIG_TCPIP_RECVMBOX_SIZE=32 1599 | CONFIG_TCP_MAXRTX=12 1600 | CONFIG_TCP_SYNMAXRTX=12 1601 | CONFIG_TCP_MSS=1440 1602 | CONFIG_TCP_MSL=60000 1603 | CONFIG_TCP_SND_BUF_DEFAULT=5744 1604 | CONFIG_TCP_WND_DEFAULT=5744 1605 | CONFIG_TCP_RECVMBOX_SIZE=6 1606 | CONFIG_TCP_QUEUE_OOSEQ=y 1607 | CONFIG_TCP_OVERSIZE_MSS=y 1608 | # CONFIG_TCP_OVERSIZE_QUARTER_MSS is not set 1609 | # CONFIG_TCP_OVERSIZE_DISABLE is not set 1610 | CONFIG_UDP_RECVMBOX_SIZE=6 1611 | CONFIG_TCPIP_TASK_STACK_SIZE=3072 1612 | CONFIG_TCPIP_TASK_AFFINITY_NO_AFFINITY=y 1613 | # CONFIG_TCPIP_TASK_AFFINITY_CPU0 is not set 1614 | # CONFIG_TCPIP_TASK_AFFINITY_CPU1 is not set 1615 | CONFIG_TCPIP_TASK_AFFINITY=0x7FFFFFFF 1616 | # CONFIG_PPP_SUPPORT is not set 1617 | CONFIG_ESP32_TIME_SYSCALL_USE_RTC_HRT=y 1618 | CONFIG_ESP32_TIME_SYSCALL_USE_RTC_FRC1=y 1619 | # CONFIG_ESP32_TIME_SYSCALL_USE_RTC is not set 1620 | # CONFIG_ESP32_TIME_SYSCALL_USE_HRT is not set 1621 | # CONFIG_ESP32_TIME_SYSCALL_USE_FRC1 is not set 1622 | # CONFIG_ESP32_TIME_SYSCALL_USE_NONE is not set 1623 | CONFIG_ESP32_PTHREAD_TASK_PRIO_DEFAULT=5 1624 | CONFIG_ESP32_PTHREAD_TASK_STACK_SIZE_DEFAULT=3072 1625 | CONFIG_ESP32_PTHREAD_STACK_MIN=768 1626 | CONFIG_ESP32_DEFAULT_PTHREAD_CORE_NO_AFFINITY=y 1627 | # CONFIG_ESP32_DEFAULT_PTHREAD_CORE_0 is not set 1628 | # CONFIG_ESP32_DEFAULT_PTHREAD_CORE_1 is not set 1629 | CONFIG_ESP32_PTHREAD_TASK_CORE_DEFAULT=-1 1630 | CONFIG_ESP32_PTHREAD_TASK_NAME_DEFAULT="pthread" 1631 | CONFIG_SPI_FLASH_WRITING_DANGEROUS_REGIONS_ABORTS=y 1632 | # CONFIG_SPI_FLASH_WRITING_DANGEROUS_REGIONS_FAILS is not set 1633 | # CONFIG_SPI_FLASH_WRITING_DANGEROUS_REGIONS_ALLOWED is not set 1634 | # CONFIG_ESP32_ULP_COPROC_ENABLED is not set 1635 | CONFIG_SUPPRESS_SELECT_DEBUG_OUTPUT=y 1636 | CONFIG_SUPPORT_TERMIOS=y 1637 | CONFIG_SEMIHOSTFS_MAX_MOUNT_POINTS=1 1638 | # End of deprecated options 1639 | -------------------------------------------------------------------------------- /src/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | # This file was automatically generated for projects 2 | # without default 'CMakeLists.txt' file. 3 | 4 | FILE(GLOB_RECURSE app_sources ${CMAKE_SOURCE_DIR}/src/*.*) 5 | 6 | idf_component_register(SRCS ${app_sources}) 7 | -------------------------------------------------------------------------------- /src/main.cpp: -------------------------------------------------------------------------------- 1 | #ifdef UNIT_TEST 2 | #include "ArduinoFake.h" 3 | #else 4 | #include "Arduino.h" 5 | #endif 6 | 7 | #define ARDUINOJSON_USE_LONG_LONG 1 8 | #define ARDUINOJSON_USE_DOUBLE 1 9 | 10 | #include "src/config.h" 11 | #include "src/moveConfig.h" 12 | #include "src/rmtStepper.h" 13 | #include "src/genStepper.h" 14 | #include "src/state.h" 15 | #include "src/Encoder.h" 16 | #include "Bounce2.h" 17 | #include "esp_err.h" 18 | #include "esp_log.h" 19 | #include "yasm.h" 20 | #include "src/web.h" 21 | #include "src/display.h" 22 | #include "src/motion.h" 23 | #include "src/Controls.h" 24 | #include "src/BounceMode.h" 25 | #include "src/myperfmon.h" 26 | #include "src/Machine.h" 27 | #include "src/led.h" 28 | 29 | // init static members 30 | 31 | Gear::State GenStepper::State::mygear; 32 | rmtStepper::State GenStepper::State::zstepper; 33 | int GenStepper::State::nom; 34 | int GenStepper::State::den; 35 | int GenStepper::State::position; 36 | 37 | int32_t MoveConfig::State::moveDistanceSteps ; 38 | bool MoveConfig::State::waitForSync ; 39 | bool MoveConfig::State::moveDirection ; 40 | int32_t MoveConfig::State::moveTargetSteps ; 41 | int MoveConfig::State::stopPos ; 42 | int MoveConfig::State::stopNeg ; 43 | bool MoveConfig::State::spindle_handedness ; 44 | double MoveConfig::State::pitch ; 45 | double MoveConfig::State::rapidPitch ; 46 | double MoveConfig::State::oldPitch ; 47 | //bool MoveConfig::State::isAbs ; 48 | bool MoveConfig::State::useStops ; 49 | int Gear::State::next; 50 | int Gear::State::prev; 51 | int Gear::State::last; 52 | 53 | void setup() { 54 | 55 | led_init(); 56 | Serial.begin(115200); 57 | 58 | 59 | 60 | init_motion(); 61 | 62 | init_machine(); 63 | 64 | init_controls(); 65 | 66 | //setFactor(); 67 | gs.setELSFactor(mc.pitch); 68 | 69 | init_web(); 70 | 71 | 72 | esp_log_level_set("perfmon", ESP_LOG_DEBUG); 73 | esp_err_t e = perfmon_start(); 74 | if(e != ESP_OK){ 75 | Serial.println("perfmon failed to start "); 76 | Serial.println(e); 77 | } 78 | bounce_yasm.next(BounceIdleState); 79 | 80 | init_encoder(); 81 | 82 | 83 | Serial.println("setup done"); 84 | } 85 | 86 | void loop() { 87 | do_web(); 88 | 89 | sendUpdates(); 90 | 91 | do_rpm(); 92 | do_state(); 93 | 94 | } 95 | -------------------------------------------------------------------------------- /src/src/BounceMode.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include "config.h" 3 | #include 4 | #include "BounceMode.h" 5 | #include "state.h" 6 | #include "Machine.h" 7 | #include "web.h" 8 | #include "motion.h" 9 | #include "genStepper.h" 10 | #include "moveConfig.h" 11 | 12 | YASM bounce_yasm; 13 | volatile bool bouncing = false; 14 | int old_moveDistanceSteps = 0; 15 | 16 | Neotimer state_timer(200); 17 | 18 | void do_state(){ 19 | if(state_timer.repeat()){ 20 | bounce_yasm.run(); 21 | } 22 | 23 | } 24 | 25 | void start_move(){ 26 | Serial.println("Bounce Start Move Called"); 27 | jogging = true; 28 | init_pos_feed(); 29 | } 30 | 31 | void BounceIdleState(){ 32 | if(bounce_yasm.isFirstRun()){ 33 | //updateMode(SLAVE_READY,RunMode::SLAVE_READY); 34 | //run_mode = RunMode::BounceIdle; 35 | updateStateDoc(); 36 | return; 37 | } 38 | else if(bouncing){ 39 | Serial.println("Bounce Init"); 40 | } 41 | 42 | } 43 | 44 | void BounceMoveState(){ 45 | if(bounce_yasm.isFirstRun()){ 46 | printf("Entering Bounce Move Mode pitch: %f\n",mc.pitch); 47 | bool d = mc.setStops(gs.position); 48 | bool z_dir = gs.zstepper.setDir(d); 49 | printf("z_dir was: %d\n",z_dir); 50 | gs.setELSFactor(mc.pitch); 51 | start_move(); 52 | updateMode(RunMode::BounceMove); 53 | //bounce_yasm.next(BounceMoveState); 54 | return; 55 | } 56 | else if(!jogging){ 57 | updateStateDoc(); 58 | Serial.println("Move Done, starting rapid"); 59 | bounce_yasm.next(BounceRapidState); 60 | } 61 | } 62 | 63 | void BounceRapidState(){ 64 | if(bounce_yasm.isFirstRun()){ 65 | printf(" Entering Rapid Mode pitch: %f",mc.rapidPitch); 66 | // TODO: yuck refactor this 67 | mc.oldPitch = mc.pitch; 68 | //pitch = rapids; 69 | //mc.pitch = mc.rapidPitch; 70 | old_moveDistanceSteps = mc.moveDistanceSteps; 71 | mc.moveDistanceSteps = -mc.moveDistanceSteps; 72 | rapiding = true; 73 | gs.setELSFactor(mc.rapidPitch); 74 | mc.setStops(gs.position); 75 | start_move(); 76 | updateStateDoc(); 77 | return; 78 | } 79 | else if(!rapiding){ 80 | Serial.println("Rapid Done, going Idle"); 81 | mc.pitch = mc.oldPitch; 82 | mc.moveDistanceSteps = old_moveDistanceSteps; 83 | bouncing = false; 84 | jogging = false; 85 | 86 | // not sure how isFirstRun works !? 87 | //bounce_yasm.next(BounceIdleState); 88 | //bounce_yasm.next(slaveJogReadyState); 89 | //RunMode(SLAVE_JOG_READY); 90 | //updateStateDoc(); 91 | //bounce_yasm.next(slaveJogReadyState,true); 92 | setRunMode((int)RunMode::SLAVE_JOG_READY); 93 | Serial.println("Bounce Mode done"); 94 | return; 95 | } 96 | 97 | } 98 | -------------------------------------------------------------------------------- /src/src/BounceMode.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | #include "yasm.h" 3 | 4 | extern YASM bounce_yasm; 5 | 6 | extern volatile bool bouncing; 7 | extern double old_jog_mm; 8 | 9 | void do_state(); 10 | void BounceMoveState(); 11 | void BounceIdleState(); 12 | void BounceRapidState(); 13 | -------------------------------------------------------------------------------- /src/src/Controls.cpp: -------------------------------------------------------------------------------- 1 | #include "Controls.h" 2 | 3 | #include "config.h" 4 | 5 | #define BOUNCE_LOCK_OUT 6 | #include 7 | #include "neotimer.h" 8 | #include 9 | #include "rmtStepper.h" 10 | #include "gear.h" 11 | #include "Machine.h" 12 | #include "Encoder.h" 13 | #include "log.h" 14 | #include "state.h" 15 | #include "Stepper.h" 16 | #include "display.h" 17 | #include "web.h" 18 | #include "genStepper.h" 19 | #include "motion.h" 20 | #include "BounceMode.h" 21 | 22 | Neotimer button_print_timer = Neotimer(2000); 23 | Neotimer dro_timer = Neotimer(600); 24 | 25 | 26 | uint8_t menu = 3; 27 | int pitch_menu= 1; 28 | 29 | 30 | #ifdef DEBUG_CPU_STATS 31 | char stats[ 2048]; 32 | #undef configGENERATE_RUN_TIME_STATS 33 | #define configGENERATE_RUN_TIME_STATS 1 34 | #undef configUSE_STATS_FORMATTING_FUNCTIONS 35 | #define configUSE_STATS_FORMATTING_FUNCTIONS 1 36 | #endif 37 | 38 | 39 | void init_controls(){ 40 | bounce_yasm.next(startupState); 41 | } 42 | 43 | 44 | 45 | 46 | void updateMode(RunMode run){ 47 | Serial.print("updating modes: "); 48 | Serial.println((int)run); 49 | run_mode = run; 50 | updateStateDoc(); 51 | } 52 | 53 | void startupState(){ 54 | if(bounce_yasm.isFirstRun()){ 55 | updateMode(RunMode::STARTUP); 56 | web = true; 57 | } 58 | } 59 | 60 | void slaveJogReadyState(){ 61 | if(bounce_yasm.isFirstRun()){ 62 | updateMode(RunMode::SLAVE_JOG_READY); 63 | //setFactor(); 64 | //gs.setELSFactor(pitch); 65 | web = true; 66 | return; 67 | } 68 | } 69 | 70 | 71 | // This is "slave jog" status mode, "slave" status is in SlaveMode.cpp 72 | void slaveJogStatusState(){ 73 | if(bounce_yasm.isFirstRun()){ 74 | updateMode(RunMode::RUNNING); 75 | web = false; 76 | } 77 | } 78 | 79 | 80 | 81 | /* replace with genStepper impl 82 | void setHobbFactor(){ 83 | int den = lead_screw_pitch * motor_steps; 84 | int nom = spindle_encoder_resolution * pitch; 85 | 86 | // 87 | Serial.printf("nom: %d den: %d",nom,den); 88 | 89 | // check ratio to be sure it can be done 90 | if (!gear.setRatio(nom,den)){ 91 | sprintf(el.buf,"Bad Ratio: Den: %d Nom: %d\n",nom,den); 92 | el.error(); 93 | pitch = oldPitch; 94 | return; 95 | } 96 | } 97 | */ 98 | 99 | //this defines the parameters for the thread and turning for both metric and imperial threads 100 | 101 | 102 | -------------------------------------------------------------------------------- /src/src/Controls.h: -------------------------------------------------------------------------------- 1 | #ifndef _Controls_h 2 | #define _Controls_h 3 | 4 | #include 5 | #include "config.h" 6 | #include "yasm.h" 7 | 8 | //#include 9 | 10 | // btn pins 11 | 12 | 13 | // Left Button 14 | #define LBP 15 15 | // Right Button 16 | #define RBP 2 17 | // Menu switch button 18 | #define SBP 14 19 | // Up Button 20 | #define UBP 4 21 | // Down Button 22 | #define DBP 16 23 | // Modifier button 24 | #define MBP 0 25 | 26 | extern YASM btn_yasm; 27 | 28 | void init_controls(void); 29 | void read_buttons(void); 30 | 31 | void handleLBP(void); 32 | void handleRBP(void); 33 | void handleSBP(void); 34 | void handleUBP(void); 35 | void handleDBP(void); 36 | void setHobbFactor(void); 37 | void feed_parameters(void); 38 | void startupState(void); 39 | void slaveJogReadyState(void); 40 | void feedingState(void); 41 | void slaveJogStatusState(void); 42 | void resetToolPos(void); 43 | void updateMode(RunMode run); 44 | void slaveJogPosState(); 45 | 46 | #endif 47 | -------------------------------------------------------------------------------- /src/src/DebugMode.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include "config.h" 3 | #include "yasm.h" 4 | #include "web.h" 5 | #include "controls.h" 6 | #include "stepper.h" 7 | #include "BounceMode.h" 8 | 9 | 10 | void debugState(){ 11 | if(bounce_yasm.isFirstRun()){ 12 | updateMode(RunMode::DEBUG_READY); 13 | web = true; 14 | } 15 | 16 | } 17 | -------------------------------------------------------------------------------- /src/src/DebugMode.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include 4 | #include "config.h" 5 | 6 | void debugState(void); -------------------------------------------------------------------------------- /src/src/Encoder.cpp: -------------------------------------------------------------------------------- 1 | #include "Encoder.h" 2 | #include "Stepper.h" 3 | #include "motion.h" 4 | #include "config.h" 5 | #include "state.h" 6 | 7 | Encoder encoder = Encoder(EA, EB, 600); 8 | volatile int64_t spindlePos = 0; 9 | volatile int vEncSpeed = 0; 10 | volatile bool vEncStopped = true; 11 | int spindle_encoder_resolution = ENCODER_RESOLUTION ; 12 | 13 | int64_t last_count = 0; 14 | 15 | Neotimer rpm_timer = Neotimer(100); 16 | 17 | int virtEncoderCount = 0; 18 | bool virtEncoderEnable = false; 19 | bool virtEncoderDir = true; 20 | 21 | void IRAM_ATTR doA(){encoder.handleA();} 22 | void IRAM_ATTR doB(){encoder.handleB();} 23 | 24 | static int64_t pulse_start = 0; 25 | static int64_t pulse_stop = 0; 26 | static int64_t total_times = 0; 27 | double avg_times = 0; 28 | static int64_t timerdelta = 0; 29 | int runs = 0; 30 | static const char* TAG_a = "T"; 31 | 32 | 33 | 34 | void init_encoder(){ 35 | encoder.init(); 36 | encoder.enableInterrupts(doA, doB); 37 | } 38 | 39 | void do_rpm(){ 40 | if(rpm_timer.repeat()){ 41 | // TODO: put this in the webUI 42 | long count_diff = abs(last_count - encoder.pulse_counter); 43 | double revolutions = (double) count_diff / spindle_encoder_resolution; 44 | rpm = revolutions * 10 * 60; 45 | last_count = encoder.pulse_counter; 46 | } 47 | } 48 | 49 | TaskHandle_t vEncHandle = NULL; 50 | 51 | void vEncTask(void *param){ 52 | for(;;){ 53 | if(vEncSpeed > 0){ 54 | for(int i =0;i<11;i++){ 55 | encoder.setCount((encoder.pulse_counter+ 1)); 56 | taskYIELD(); 57 | } 58 | 59 | }else{ 60 | for(int i =0;i<11;i++){ 61 | encoder.setCount((encoder.pulse_counter- 1)); 62 | taskYIELD(); 63 | } 64 | 65 | } 66 | vTaskDelay(vEncSpeed/portTICK_PERIOD_MS); 67 | } 68 | } 69 | 70 | void stopVenc(){ 71 | if(vEncHandle != NULL) { 72 | Serial.println("stopping venc"); 73 | vTaskDelete(vEncHandle); 74 | vEncStopped = true; 75 | } 76 | } 77 | 78 | void startVenc(){ 79 | Serial.println("Starting venc"); 80 | xTaskCreate( 81 | vEncTask, 82 | "vEnc", 83 | 4000, 84 | NULL, 85 | 1, 86 | &vEncHandle 87 | ); 88 | vEncStopped = false; 89 | 90 | } 91 | 92 | 93 | 94 | // B channel 95 | void IRAM_ATTR Encoder::handleB() { 96 | //pulse_start = esp_timer_get_time(); 97 | int B = digitalRead(pinB); 98 | switch (quadrature){ 99 | case Quadrature::ON: 100 | // // CPR = 4xPPR 101 | if ( B != B_active ) { 102 | dir = (A_active != B_active); 103 | pulse_counter += dir ? 1 : -1; 104 | pulse_timestamp = esp_timer_get_time();// _micros(); 105 | B_active = B; 106 | processMotion(); 107 | } 108 | break; 109 | case Quadrature::OFF: 110 | // CPR = PPR 111 | if(B && !digitalRead(pinA)){ 112 | pulse_counter--; 113 | dir = false; 114 | pulse_timestamp = esp_timer_get_time();//_micros(); 115 | processMotion(); 116 | } 117 | break; 118 | } 119 | //pulse_stop = esp_timer_get_time(); 120 | //startStatTask(); 121 | } 122 | 123 | // Encoder interrupt callback functions 124 | // A channel 125 | void IRAM_ATTR Encoder::handleA() { 126 | pulse_start = esp_timer_get_time(); 127 | int A = digitalRead(pinA); 128 | switch (quadrature){ 129 | case Quadrature::ON: 130 | // CPR = 4xPPR 131 | if ( A != A_active ) { 132 | dir = (A_active == B_active); 133 | pulse_counter += dir ? 1 : -1; 134 | pulse_timestamp = esp_timer_get_time();// _micros(); 135 | A_active = A; 136 | processMotion(); 137 | } 138 | break; 139 | case Quadrature::OFF: 140 | // CPR = PPR 141 | if(A && !digitalRead(pinB)){ 142 | pulse_counter++; 143 | dir = true; 144 | pulse_timestamp = esp_timer_get_time();//_micros(); 145 | processMotion(); 146 | } 147 | break; 148 | } 149 | pulse_stop = esp_timer_get_time(); 150 | //startStatTask(); 151 | } 152 | 153 | Encoder::Encoder(int _encA, int _encB , double _ppr){ 154 | 155 | // Encoder measurement structure init 156 | // hardware pins 157 | pinA = _encA; 158 | pinB = _encB; 159 | // counter setup 160 | pulse_counter = 0; 161 | pulse_timestamp = 0; 162 | 163 | dir = true; 164 | start = 1; 165 | 166 | cpr = _ppr; 167 | A_active = 0; 168 | B_active = 0; 169 | 170 | // velocity calculation variables 171 | prev_Th = 0; 172 | pulse_per_second = 0; 173 | prev_pulse_counter = 100; 174 | prev_timestamp_us = esp_timer_get_time();//_micros(); 175 | 176 | pullup = ENCODER_PULLUP; 177 | // enable quadrature encoder by default 178 | quadrature = Quadrature::ON; 179 | } 180 | double Encoder::getAngle(){ 181 | return natural_direction * _2PI * (pulse_counter) / ((double)cpr); 182 | } 183 | // initialize counter to zero 184 | // TODO: not implmeented, need some nottion of work coordinates developed 185 | double Encoder::initRelativeZero(){ 186 | long angle_offset = -pulse_counter; 187 | pulse_counter = 0; 188 | pulse_timestamp = esp_timer_get_time();//_micros(); 189 | return _2PI * (angle_offset) / ((double )cpr); 190 | } 191 | 192 | void Encoder::init(){ 193 | 194 | // Encoder - check if pullup needed for your encoder 195 | if(pullup == Pullup::INTERN_PULLUP){ 196 | Serial.println("Using Internal PULLUP"); 197 | pinMode(pinA, INPUT_PULLUP); 198 | pinMode(pinB, INPUT_PULLUP); 199 | //if(hasIndex()) pinMode(index_pin,INPUT_PULLUP); 200 | }else if(pullup == Pullup::INTERN_PULLDOWN){ 201 | Serial.println("Using Internal PULLDOWN"); 202 | pinMode(pinA, INPUT_PULLDOWN); 203 | pinMode(pinB, INPUT_PULLDOWN); 204 | }else 205 | { 206 | Serial.println("Using External PULLUP/PULLDOWN"); 207 | pinMode(pinA, INPUT); 208 | pinMode(pinB, INPUT); 209 | //if(hasIndex()) pinMode(index_pin,INPUT); 210 | } 211 | 212 | // counter setup 213 | pulse_counter = 0; 214 | pulse_timestamp = esp_timer_get_time();//_micros(); 215 | // velocity calculation variables 216 | prev_Th = 0; 217 | pulse_per_second = 0; 218 | prev_pulse_counter = -1; 219 | prev_timestamp_us = esp_timer_get_time();//_micros(); 220 | dir = true; 221 | 222 | // initial cpr = PPR 223 | // change it if the mode is quadrature 224 | if(quadrature == Quadrature::ON) cpr = 4*cpr; 225 | start = cpr; 226 | 227 | } 228 | 229 | 230 | void Encoder::enableInterrupts(void (*doA)(), void(*doB)()){ 231 | // attach interrupt if functions provided 232 | // pinning to core 0 is slow and creates jitter 233 | attachInterrupt(digitalPinToInterrupt(encoder.pinA), doA, CHANGE); 234 | attachInterrupt(digitalPinToInterrupt(encoder.pinB), doB, CHANGE); 235 | } 236 | 237 | void IRAM_ATTR Encoder::setCount(int64_t count){ 238 | // TODO: why do you need these? 239 | pulse_counter = count; 240 | processMotion(); 241 | } 242 | int64_t IRAM_ATTR Encoder::getCount(){ 243 | // TODO: why not just read the value? 244 | return pulse_counter; 245 | } 246 | 247 | void IRAM_ATTR statTask(void *ptr){ 248 | // do stuff 249 | if(runs < 10000){ 250 | timerdelta = pulse_stop - pulse_start; 251 | total_times = total_times + timerdelta; 252 | runs++; 253 | }else{ 254 | avg_times = (double)(total_times / runs); 255 | startPrintTask(); 256 | runs = 0; 257 | total_times = 0; 258 | } 259 | vTaskDelete( NULL ); 260 | } 261 | 262 | void IRAM_ATTR printTask(void *ptr){ 263 | ESP_LOGE(TAG_a,"\n\t avg: %lf start: %lld : stop %lld\n",avg_times,pulse_start,pulse_stop); 264 | vTaskDelete( NULL); 265 | } 266 | 267 | void startStatTask(){ 268 | xTaskCreate( 269 | statTask, /* Task function. */ 270 | "statTask", /* String with name of task. */ 271 | 1000, /* Stack size in words. */ 272 | NULL, /* Parameter passed as input of the task */ 273 | 3, /* Priority of the task. */ 274 | NULL); 275 | } 276 | 277 | void startPrintTask(){ 278 | xTaskCreate( 279 | printTask, /* Task function. */ 280 | "printTask", /* String with name of task. */ 281 | 10000, /* Stack size in words. */ 282 | NULL, /* Parameter passed as input of the task */ 283 | 1, /* Priority of the task. */ 284 | NULL); 285 | } 286 | 287 | -------------------------------------------------------------------------------- /src/src/Encoder.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include "config.h" 4 | #include "neotimer.h" 5 | 6 | extern volatile int vEncSpeed; 7 | extern volatile bool vEncStopped; 8 | extern int spindle_encoder_resolution; 9 | extern Neotimer rpm_timer; 10 | extern double avg_times; 11 | 12 | enum Quadrature 13 | { 14 | ON, //!< Enable quadrature mode CPR = 4xPPR 15 | OFF //!< Disable quadrature mode / CPR = PPR 16 | }; 17 | 18 | enum Direction 19 | { 20 | CW = 1, // clockwise 21 | CCW = -1, // counter clockwise 22 | UNKNOWN = 0 // not yet known or invalid state 23 | }; 24 | 25 | /** 26 | * Pullup configuration structure 27 | */ 28 | enum Pullup 29 | { 30 | INTERN_PULLUP, //!< Use internal pullups 31 | INTERN_PULLDOWN, 32 | EXTERN //!< Use external pullups 33 | }; 34 | 35 | void init_encoder(void); 36 | void do_rpm(void); 37 | void stopVenc(); 38 | void startVenc(); 39 | void startStatTask(void); 40 | void startPrintTask(void); 41 | 42 | // sign function 43 | #define _sign(a) (((a) < 0) ? -1 : ((a) > 0)) 44 | #define _round(x) ((x) >= 0 ? (long)((x) + 0.5) : (long)((x)-0.5)) 45 | #define _constrain(amt, low, high) ((amt) < (low) ? (low) : ((amt) > (high) ? (high) : (amt))) 46 | 47 | // utility defines 48 | #define _2_SQRT3 1.15470053838 49 | #define _SQRT3 1.73205080757 50 | #define _1_SQRT3 0.57735026919 51 | #define _SQRT3_2 0.86602540378 52 | #define _SQRT2 1.41421356237 53 | #define _120_D2R 2.09439510239 54 | #define _PI 3.14159265359 55 | #define _PI_2 1.57079632679 56 | #define _PI_3 1.0471975512 57 | #define _2PI 6.28318530718 58 | #define _3PI_2 4.71238898038 59 | 60 | class Encoder 61 | { 62 | public: 63 | Encoder(int encA, int encB, double ppr); 64 | 65 | /** encoder initialise pins */ 66 | void init(); 67 | void enableInterrupts(void (*doA)() = nullptr, void (*doB)() = nullptr); 68 | 69 | // Encoder interrupt callback functions 70 | /** A channel callback function */ 71 | void handleA(); 72 | /** B channel callback function */ 73 | void handleB(); 74 | double getAngle(); 75 | double initRelativeZero(); 76 | double initAbsoluteZero(); 77 | int pinA; //!< encoder hardware pin A 78 | int pinB; //!< encoder hardware pin B 79 | int cpr; 80 | Pullup pullup; 81 | int quadrature; 82 | int natural_direction = Direction::CW; 83 | void setCount(int64_t count); 84 | int64_t getCount(); 85 | volatile int64_t pulse_counter; 86 | volatile int64_t prev_pulse_counter; 87 | volatile bool dir; 88 | volatile int start; 89 | 90 | private: 91 | //!< current pulse counter 92 | volatile long pulse_timestamp; //!< last impulse timestamp in us 93 | volatile int A_active; //!< current active states of A channel 94 | volatile int B_active; //!< current active states of B channel 95 | double prev_Th, pulse_per_second; 96 | 97 | volatile long prev_timestamp_us; 98 | }; 99 | 100 | // encoder instance 101 | // Pins defines in config.h 102 | extern Encoder encoder; 103 | -------------------------------------------------------------------------------- /src/src/Machine.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include "config.h" 3 | #include "Machine.h" 4 | #include "state.h" 5 | #include "Stepper.h" 6 | 7 | uint8_t motor_type = MOTOR_TYPE; 8 | 9 | //TODO: is this redundant? 10 | double lead_screw_pitch = 2.0; 11 | 12 | //TODO configure using config.h 13 | double backlash = 0.0; 14 | 15 | void init_machine(){ 16 | 17 | 18 | if(motor_type ==1) 19 | native_steps = 200; 20 | if(motor_type ==2) 21 | native_steps = 400; 22 | 23 | // motor steps per mm 24 | motor_steps = (microsteps * native_steps) ; 25 | stepsPerMM = motor_steps / lead_screw_pitch; 26 | mmPerStep = (double) 1/stepsPerMM; 27 | init_stepper(); 28 | } 29 | 30 | 31 | -------------------------------------------------------------------------------- /src/src/Machine.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | //I suggest making a leadscrew class that owns things like this, leadscrew measurement system, etc... 4 | extern double lead_screw_pitch; 5 | extern int microsteps; 6 | 7 | 8 | //threading parameters should be owned by and controlled by a thread class, 9 | // which inherits from a feeding class, which inherits from a simple movement class. 10 | // that way you can pass the object in to the motion control class as params and it knows everything it needs to 11 | // about the current mode, such as encoder steps per spindle rev. It can be passed in the event into the 12 | // state machine handlers too, for switching modes, etc 13 | // jog can inherit from feeding 14 | // feeding can contain a Bounce object, containing params for the bounce behavior. It can always run the bounce logic 15 | // and depending on the Bounce object params, do the auto return to the start or not, in any mode. 16 | 17 | extern double backlash; 18 | 19 | void init_machine(void); 20 | -------------------------------------------------------------------------------- /src/src/SlaveMode.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include "config.h" 3 | #include 4 | #include "state.h" 5 | #include "web.h" 6 | #include "Controls.h" 7 | #include "motion.h" 8 | #include "BounceMode.h" 9 | 10 | 11 | void SlaveModeReadyState(){ 12 | if(bounce_yasm.isFirstRun()){ 13 | updateMode(RunMode::SLAVE_READY); 14 | web = true; 15 | } 16 | } 17 | 18 | void slaveStatusState(){ 19 | if(bounce_yasm.isFirstRun()){ 20 | updateMode(RunMode::RUNNING); 21 | // ?? this was off, why? 22 | web = true; 23 | } 24 | } 25 | 26 | void FeedModeReadyState(){ 27 | if(bounce_yasm.isFirstRun()){ 28 | updateMode(RunMode::FEED_READY); 29 | 30 | } 31 | } 32 | 33 | void slaveFeedingState(){ 34 | if(bounce_yasm.isFirstRun()){ 35 | 36 | // TODO: should check for RPM 0 for this state? 37 | updateMode(RunMode::RUNNING); 38 | feeding = true; 39 | web = false; 40 | } 41 | 42 | } 43 | -------------------------------------------------------------------------------- /src/src/SlaveMode.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include 4 | #include "config.h" 5 | 6 | 7 | void SlaveModeReadyState(void); 8 | void slaveStatusState(void); 9 | void slaveFeedingState(void); 10 | void FeedModeReadyState(void); 11 | -------------------------------------------------------------------------------- /src/src/Stepper.cpp: -------------------------------------------------------------------------------- 1 | #include "Stepper.h" 2 | #include 3 | #include "gear.h" 4 | #include "rmtStepper.h" 5 | #include "genStepper.h" 6 | #include "state.h" 7 | 8 | int microsteps = Z_MICROSTEPPING; 9 | 10 | int native_steps = Z_NATIVE_STEPS_PER_REV; 11 | int motor_steps = Z_MICROSTEPPING * Z_NATIVE_STEPS_PER_REV; 12 | 13 | 14 | // number of ticks to wait between timer events 15 | int timertics = 10; 16 | 17 | // used to figure out how many steps we need to get to the right position 18 | // delta is in stepper steps 19 | volatile int delta = 0; 20 | 21 | // this is the time between a low and the next high or dir and step 22 | volatile int delay_ticks = 3; 23 | volatile int previous_delay_ticks = 0; 24 | volatile int min_delay_ticks = 5; 25 | 26 | 27 | int use_limit = false; 28 | volatile int64_t calculated_stepper_pulses=0; 29 | 30 | 31 | volatile bool pos_feeding = false; 32 | 33 | 34 | /* 35 | 36 | Refactoring notes: 37 | 38 | calculate max speed and create timer with slower frequency to act on encoder ticks. 39 | rip everything not related to step signal gen out of 80mhz timer or use RMT stepping. 40 | 41 | Add some debugging execution time checks to make sure the calculations are fast enough. 42 | Consider pinning tasks to cores to distribute load. One core is pegged the other is mostly idle. 43 | 44 | try to make code testable but also can run in timer. research how to do this. 45 | 46 | consider moving display code into state functions 47 | 48 | 49 | */ 50 | 51 | 52 | 53 | void init_stepper(){ 54 | 55 | pinMode(Z_DIR_PIN, OUTPUT); 56 | pinMode(Z_STEP_PIN, OUTPUT); 57 | 58 | stepsPerMM = motor_steps / lead_screw_pitch; 59 | 60 | 61 | gs.zstepper.config.channel = RMT_CHANNEL_0; 62 | gs.zstepper.config.stepPin = (gpio_num_t) Z_STEP_PIN; 63 | gs.zstepper.config.dirPin = (gpio_num_t) Z_DIR_PIN; 64 | 65 | gs.zstepper.init(); 66 | 67 | 68 | } 69 | -------------------------------------------------------------------------------- /src/src/Stepper.h: -------------------------------------------------------------------------------- 1 | #ifndef _Stepper_h 2 | #define _Stepper_h 3 | 4 | #include 5 | #include "config.h" 6 | 7 | 8 | 9 | // number of ticks to wait between timer events 10 | extern int timertics; 11 | 12 | // used to figure out how many steps we need to get to the right position 13 | // delta is in stepper steps 14 | extern volatile int delta; 15 | 16 | // this is the time between a low and the next high or dir and step 17 | extern volatile int delay_ticks; 18 | extern volatile int previous_delay_ticks; 19 | extern volatile int min_delay_ticks; 20 | 21 | 22 | 23 | extern int use_limit; 24 | extern volatile int64_t calculated_stepper_pulses; 25 | 26 | 27 | // TOOD: move to a machine state struct 28 | extern volatile bool pos_feeding; 29 | 30 | extern int microsteps; 31 | 32 | extern int native_steps; 33 | extern int motor_steps; 34 | 35 | 36 | 37 | void init_stepper(void); 38 | bool getDir(void); 39 | bool setDir(bool); 40 | void updatePosition(); 41 | void init_feed(); 42 | 43 | #endif 44 | -------------------------------------------------------------------------------- /src/src/config.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | #include 3 | #include "util.h" 4 | 5 | // TODO: need a way to tie versions of the firmware to compatable versions of the UI 6 | // also need to have a compiled UI version linked in firmware releases 7 | #define VSN "0.0.2" 8 | 9 | #ifndef configured 10 | #error WARNING: no config.ini detected. Please copy config.ini.template to config.ini and customize it. 11 | #endif 12 | /************* Machine Configuration *************/ 13 | 14 | // TODO: no buttons will work, need to fixor this if anyone wants buttons 15 | //#define HAS_BUTTONS 16 | 17 | //web interface hostname 18 | #ifndef HOSTNAME 19 | #error Set your HOSTNAME in your config.ini 20 | #endif 21 | 22 | #ifndef WIFI_SSID 23 | #error Set your WIFI_SSID in your config.ini 24 | #endif 25 | 26 | #ifndef WIFI_PASSWORD 27 | #error Set your WIFI_PASSWORD in your config.ini 28 | #endif 29 | #ifndef LEADSCREW_LEAD 30 | #error Set your LEADSCREW_LEAD in your config.ini 31 | #endif 32 | 33 | // Stepper driver Pins 34 | //NOTE: it's recommended to avoid pins 12 to 18 if you want to use JTAG for on circuit debugging 35 | #ifndef Z_STEP_PIN 36 | #error Set your Z_STEP_PIN in your config.ini 37 | #endif 38 | 39 | #ifndef Z_DIR_PIN 40 | #error Set your Z_DIR_PIN in your config.ini 41 | #endif 42 | 43 | //I don't think this is needed, we can infer this by microstepping and native steps per rev 44 | #define MOTOR_TYPE 1 // 1 is 1.8 degree, 2 is .9 degree 45 | 46 | #ifndef Z_NATIVE_STEPS_PER_REV 47 | #error Set your Z_NATIVE_STEPS_PER_REV in your config.ini 48 | #endif 49 | 50 | #ifndef Z_MICROSTEPPING 51 | #error Set your Z_MICROSTEPPING in your config.ini 52 | #endif 53 | 54 | // Spindle Encoder pins 55 | 56 | #ifndef EA 57 | #error Set your EA in your config.ini 58 | #endif 59 | #ifndef EA 60 | #error Set your EA in your config.ini 61 | #endif 62 | /* 63 | choices are: 64 | Pullup::EXTERN //your hardware handles the pullup or pulldown, for example with a resistor to 3v3 or to gnd 65 | Pullup::INTERN_PULLDOWN //your encoder expects the MCU to pull low, and sends a high for a pulse 66 | Pullup::INTERN_PULLUP //your esp handles the pullup and your encoder pulls it down. 67 | For most common quadrature encoders, choose Extern and apply 3.3v to your encoder pins through 1.5k to 4.7k ohm resistors */ 68 | #ifndef ENCODER_PULLUP_TYPE 69 | #error Set your ENCODER_PULLUP_TYPE in your config.ini 70 | #else 71 | #define ENCODER_PULLUP Pullup::ENCODER_PULLUP_TYPE 72 | #endif 73 | 74 | 75 | //this should be ON, unless you have a good reason not to. Otherwise your leadscrew will not track reverses. 76 | #ifndef ENCODER_QUADRATURE_MODE 77 | #error Set your ENCODER_QUADRATURE_MODE in your config.ini 78 | #else 79 | #define QUADRATURE_MODE Quadrature::ENCODER_PULLUP_TYPE 80 | #endif 81 | 82 | //this is counts per rev *4 for a quadrature encoder 83 | #ifndef ENCODER_RESOLUTION 84 | #error Set your ENCODER_RESOLUTION in your config.ini 85 | #endif 86 | 87 | //use the display or not. Recommend not, it doesn't have much functionality. Set to 1 to enable. 88 | #ifndef USESSD1306 89 | #define USESSD1306 0 90 | #endif 91 | 92 | #ifndef error_led 93 | #define error_led 33 94 | #endif 95 | 96 | #ifndef wifi_led 97 | #define wifi_led 32 98 | #endif 99 | 100 | // read the cpu usage via the web server, only use for testing as it comes with bloat 101 | //#define DEBUG_CPU_STATS 102 | 103 | //TODO I think this isn't necessary since we can calculate microsteps per rev with the above and can divide the distance into steps instead of degrees 104 | #define STEPPER_DEGREES_PER_STEP 1.8 105 | -------------------------------------------------------------------------------- /src/src/display.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include "config.h" 3 | #include "util.h" 4 | 5 | 6 | 7 | 8 | -------------------------------------------------------------------------------- /src/src/display.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | extern int display_mode; 4 | 5 | void init_display(void); 6 | 7 | void do_display(void); 8 | -------------------------------------------------------------------------------- /src/src/gear.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | #include 3 | 4 | 5 | 6 | namespace Gear { 7 | struct Jump { 8 | //uint16_t count; 9 | int64_t count; 10 | int16_t delta; 11 | int error; 12 | }; 13 | 14 | // encoder counts where we have our next and previous jumps 15 | struct Jumps{ 16 | int next; 17 | int prev; 18 | int last; 19 | }; 20 | 21 | 22 | // need a set nominator/denominator that checks to ensure the slope < 1 for bresenham 23 | 24 | #pragma GCC diagnostic push 25 | #pragma GCC diagnostic ignored "-Wnarrowing" 26 | // Narrowing comes due to integer promotion in arithmetic operations 27 | // k, the encoder count delta for the next step pulse, should fit within a short integer 28 | static int32_t k; 29 | 30 | inline Jump next_jump_forward(int d, int n, int e, int64_t count) { 31 | //assert(d != 0); 32 | //assert(n != 0); 33 | // k = encoder_pulses per step 34 | k = (d - 2 * e + 2 * n - 1) / (2 * n); 35 | return {count + k, k, e + k * n - d}; 36 | } 37 | 38 | inline Jump next_jump_reverse(int d, int n, int e, int64_t count) { 39 | // k = encoder_pulses per step 40 | k = 1 + ((d + 2 * e) / (2 * n)); 41 | return {count - k, k, e - k * n + d}; 42 | } 43 | 44 | struct State { 45 | int D, N; // pulse ratio : N/D 46 | //int err = 0; 47 | int nerror = 0; 48 | int perror = 0; 49 | // what units is this, seems to be encoder tics 50 | int output_position = 0; 51 | Jumps jumps = {0,0,0}; 52 | static int next; 53 | static int prev; 54 | static int last; 55 | 56 | // TODO: stop using the 2nd arg, it has to be true 57 | void calc_jumps(int encoder_count,bool dir = true){ 58 | if(D == 0 || N == 0){ 59 | //printf("D: %d N: %d calc_jumps exiting",N,D); 60 | // TODO: how to prevent this condition? 61 | return; 62 | } 63 | Jump nx = next_jump_forward(D,N,nerror,encoder_count); 64 | Jump px = next_jump_reverse(D,N,perror,encoder_count); 65 | next = nx.count; 66 | last = encoder_count; 67 | nerror = nx.error; 68 | if(dir){ 69 | prev = px.count; 70 | perror = nx.error + D -N; 71 | } 72 | // this doesn't seem to work for !dir 73 | /* 74 | else{ 75 | jumps.prev = px.count + 1; 76 | perror = nx.error + D +N; 77 | } 78 | */ 79 | 80 | 81 | } 82 | bool setRatio(int nom, int den){ 83 | if (nom > den){ 84 | return false; 85 | } 86 | D = den; 87 | N = nom; 88 | return true; 89 | } 90 | 91 | }; 92 | 93 | 94 | 95 | /* not using this yet 96 | Range range; 97 | 98 | template 99 | void configure(const RationalNumber& ratio, int32_t start_position) { 100 | state.D = ratio.denominator(); 101 | state.N = ratio.numerator(); 102 | state.nerror = 0; 103 | state.perror = 0; 104 | range.next = next_jump_forward(ratio.denominator(), ratio.numerator(), 0, start_position); 105 | range.prev = next_jump_reverse(ratio.denominator(), ratio.numerator(), 0, start_position); 106 | } 107 | 108 | inline unsigned phase_delay(int32_t input_period, int e) { 109 | if (e < 0) e = -e; 110 | return (input_period * e) / (state.N); 111 | } 112 | */ 113 | 114 | } 115 | -------------------------------------------------------------------------------- /src/src/genStepper.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | #include "gear.h" 3 | #include "log.h" 4 | 5 | // yuck 6 | #ifdef UNIT_TEST 7 | #include "mocks.h" 8 | #else 9 | #include "rmtStepper.h" 10 | #endif 11 | 12 | 13 | namespace GenStepper { 14 | struct Config{ 15 | int dir ; 16 | const char* name; 17 | float lead_screw_pitch ; 18 | int spindle_encoder_resolution ; 19 | int native_steps ; 20 | int microsteps ; 21 | int motor_steps ; 22 | }; 23 | 24 | struct State{ 25 | static int position; 26 | float factor = 0; 27 | float offset = 0; //add to stepPosition 28 | 29 | static int32_t den; // should rarely change leadscrew or encoder resolution 30 | static int32_t nom; 31 | 32 | Config c; 33 | static Gear::State mygear; 34 | Log::Msg lm; 35 | static rmtStepper::State zstepper; 36 | 37 | 38 | // if returns true it worked 39 | inline bool setELSFactor(double pitch, bool recalculate_den = false){ 40 | if(pitch == 0){ 41 | sprintf(lm.buf,"Pitch 0, no good"); 42 | //lm.error(); 43 | return false; 44 | } 45 | 46 | if(recalculate_den == true){ 47 | GenStepper::State::den = c.lead_screw_pitch * c.spindle_encoder_resolution; 48 | printf("recalculated denominator: %i",den); 49 | } 50 | GenStepper::State::nom = c.motor_steps * pitch; 51 | if(nom == 0 || den == 0){ 52 | printf("\n\n\tStepper set factor failed, perhaps your config is bad? nom: %i den: %i\n\n",nom,den); 53 | return false; 54 | } 55 | if(!mygear.setRatio(nom,den)){ 56 | sprintf(lm.buf,"Bad Ratio: Den: %d Nom: %d\n",nom,den); 57 | //lm.error(); 58 | return false; 59 | } 60 | printf("Set ELS Factor pitch: %f nom: %d den: %d\n",pitch,nom,den); 61 | return true; 62 | } 63 | inline void setHobFactor(){ 64 | 65 | } 66 | inline bool init_gear(int64_t count){ 67 | //printf("init_gear count was: %lld \n",count); 68 | if(mygear.setRatio(nom,den)){ 69 | mygear.calc_jumps(count); 70 | mygear.last = mygear.prev; 71 | return true; 72 | }else{ 73 | printf("\n\n\n\tinit_gear setRatio failed: count: %lld nom: %i den: %i",count,nom,den); 74 | return false; 75 | } 76 | 77 | } 78 | 79 | inline void stepPos(){ 80 | zstepper.step(); 81 | position++; 82 | } 83 | inline void stepNeg(){ 84 | zstepper.step(); 85 | position--; 86 | 87 | } 88 | inline void step(){ 89 | if( zstepper.dir){ 90 | stepPos(); 91 | }else{ 92 | stepNeg(); 93 | } 94 | } 95 | 96 | }; 97 | inline State init(const char * name,Log::Msg lm,Config c){ 98 | double init_pitch = 0.1; 99 | State state; 100 | state.position = 0; 101 | state.c = c; 102 | state.c.name = name; 103 | state.lm = lm; 104 | state.nom = c.spindle_encoder_resolution * init_pitch; 105 | state.den = (int)(c.lead_screw_pitch / c.motor_steps); 106 | 107 | state.setELSFactor(init_pitch,true); 108 | state.init_gear(0); 109 | return state; 110 | 111 | } 112 | 113 | inline bool checkRatio(){ 114 | return false; 115 | } 116 | } 117 | -------------------------------------------------------------------------------- /src/src/hob.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include "config.h" 3 | #include 4 | #include "Stepper.h" 5 | #include "state.h" 6 | #include "motion.h" 7 | #include "log.h" 8 | 9 | void HobReadyState(){ 10 | if(run_mode != RunMode::HOB_RUN){ 11 | Serial.println("Enter HobReadyState"); 12 | }else{ 13 | el.error("Use HobStopState, invalid state transition"); 14 | } 15 | } 16 | 17 | void HobRunState(){ 18 | Serial.println("Enter HobRunState"); 19 | 20 | // Turn off stops, we just slave to the spindle 21 | mc.useStops = false; 22 | // flag processor and encoder to start 23 | jogging = true; 24 | init_hob_feed(); 25 | updateMode(RunMode::HOB_RUN); 26 | } 27 | 28 | void HobStopState(){ 29 | mc.useStops = true; 30 | jogging = false; 31 | //feeding = false; 32 | pos_feeding = false; 33 | updateMode(RunMode::HOB_STOP); 34 | HobReadyState(); 35 | updateMode(RunMode::HOB_READY); 36 | } 37 | -------------------------------------------------------------------------------- /src/src/hob.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | void do_hob_state(); 4 | void HobReadyState(); 5 | void HobRunState(); 6 | void HobStopState(); 7 | -------------------------------------------------------------------------------- /src/src/led.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | 4 | 5 | int error_led_delay = 100; 6 | int wifi_led_delay = 100; 7 | 8 | TaskHandle_t error_th = NULL; 9 | TaskHandle_t wifi_th = NULL; 10 | 11 | void error_task(void * parameter){ 12 | while(1){ 13 | digitalWrite(error_led,HIGH); 14 | delay(error_led_delay); 15 | digitalWrite(error_led,LOW); 16 | delay(error_led_delay); 17 | } 18 | vTaskDelete( NULL ); 19 | } 20 | 21 | void my_wifi_task(void * parameter){ 22 | while(1){ 23 | digitalWrite(wifi_led,HIGH); 24 | delay(wifi_led_delay); 25 | digitalWrite(wifi_led,LOW); 26 | delay(wifi_led_delay); 27 | } 28 | vTaskDelete( NULL ); 29 | } 30 | 31 | void startErrorTask(){ 32 | char task1Param[12] = "taskParam"; 33 | /* we create a new task here */ 34 | xTaskCreate( 35 | error_task, /* Task function. */ 36 | "errorTask", /* name of task. */ 37 | 1000, /* Stack size of task */ 38 | NULL, /* parameter of the task */ 39 | 1, /* priority of the task */ 40 | &error_th); /* Task handle to keep track of created task */ 41 | } 42 | 43 | void startWifiTask(){ 44 | 45 | /* let task1 run first then create task2 */ 46 | xTaskCreate( 47 | my_wifi_task, /* Task function. */ 48 | "task2", /* name of task. */ 49 | 10000, /* Stack size of task */ 50 | NULL, /* parameter of the task */ 51 | 1, /* priority of the task */ 52 | &wifi_th); /* Task handle to keep track of created task */ 53 | } 54 | 55 | 56 | void led_init(){ 57 | pinMode(error_led,OUTPUT); 58 | pinMode(wifi_led,OUTPUT); 59 | startErrorTask(); 60 | startWifiTask(); 61 | 62 | 63 | } 64 | 65 | 66 | void set_error_led_blink(int i){ 67 | error_led_delay = i; 68 | } 69 | 70 | 71 | void set_wifi_led_blink(int i){ 72 | wifi_led_delay = i; 73 | } 74 | -------------------------------------------------------------------------------- /src/src/led.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | void set_wifi_led_blink(int i); 4 | void set_error_led_blink(int i); 5 | void led_init(void); 6 | -------------------------------------------------------------------------------- /src/src/log.cpp: -------------------------------------------------------------------------------- 1 | #include "log.h" 2 | 3 | Log::Msg el; 4 | 5 | void Log::Msg::maybeSend(){ 6 | #ifndef UNIT_TEST 7 | sendLogP(this); 8 | #endif 9 | #ifdef UNIT_TEST 10 | 11 | #endif 12 | } 13 | 14 | void Log::Msg::error(){ 15 | if(this->t == T::WS){ 16 | Serial.print("\nWS Log: "); 17 | Serial.println(this->buf); 18 | maybeSend(); 19 | } 20 | } 21 | 22 | void Log::Msg::error(const char* s){ 23 | if(this->t == T::WS){ 24 | sprintf(buf,s); 25 | maybeSend(); 26 | Serial.println(s); 27 | } 28 | } 29 | void Log::Msg::halt(const char* s){ 30 | if(this->t == T::WS){ 31 | sprintf(buf,s); 32 | maybeSend(); 33 | Serial.println(s); 34 | } 35 | } 36 | 37 | void Log::Msg::errorTaskImpl(void* _this){ 38 | static_cast(_this)->error(); 39 | vTaskDelete(NULL); 40 | } 41 | void Log::Msg::errorTask(){ 42 | xTaskCreate(this->errorTaskImpl,"errorTask",2048,this, 5,NULL); 43 | } 44 | 45 | 46 | void Log::Msg::addMsg(const char* s){ 47 | sprintf(buf,s); 48 | } 49 | -------------------------------------------------------------------------------- /src/src/log.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | #include 3 | 4 | //#include "config.h" 5 | 6 | #ifndef UNIT_TEST 7 | #include "web.h" 8 | #endif 9 | 10 | namespace Log{ 11 | enum class T { 12 | WEB, 13 | SER, 14 | WS 15 | }; 16 | enum class Level { 17 | ERROR, 18 | WARN, 19 | INFO, 20 | HALT 21 | }; 22 | class Msg{ 23 | public: 24 | T t = T::WS; 25 | bool hasError = false; 26 | char buf[500] = ""; 27 | Level level = Level::ERROR; 28 | void maybeSend(); 29 | void error(void); 30 | void error(const char*); 31 | void halt(const char*); 32 | void addMsg(const char*); 33 | void errorTask(); 34 | static void errorTaskImpl(void* _this); 35 | }; 36 | 37 | } 38 | 39 | extern Log::Msg el; 40 | -------------------------------------------------------------------------------- /src/src/mocks.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | #include 3 | 4 | namespace rmtStepper{ 5 | struct State { 6 | bool dir = {true}; 7 | bool dir_has_changed = {false}; 8 | void step(){ 9 | //std::cout <<"step " << dir << "\n"; 10 | }; 11 | inline bool setDir(bool newDir){ 12 | dir = newDir; 13 | return dir; 14 | } 15 | inline void setDir(bool newDir,bool now){ 16 | dir = newDir; 17 | } 18 | } ; 19 | } 20 | -------------------------------------------------------------------------------- /src/src/motion.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include "motion.h" 3 | 4 | #include "config.h" 5 | 6 | #include "gear.h" 7 | // should just be using accel/decel calcs 8 | 9 | #include "Encoder.h" 10 | #include "Stepper.h" 11 | #include "state.h" 12 | #include "log.h" 13 | #include "Controls.h" 14 | #include "Machine.h" 15 | #include "genStepper.h" 16 | //#define LOG_LOCAL_LEVEL ESP_LOG_INFO 17 | #include 18 | 19 | static const char* TAG = "Mo"; 20 | 21 | 22 | // actual error is max_error * 2 since this is a range around the tool potion + and - 23 | static int max_error = 20; 24 | 25 | // not sure this is needed 26 | //volatile bool feeding = false; 27 | 28 | // this is used mostly for feed mode to flip the behaviors, spindle moving ccw moves carriage Z+ or Z- depending on 29 | // how this is set 30 | volatile bool feeding_ccw = true; 31 | 32 | char err[500] = ""; 33 | 34 | 35 | 36 | 37 | void init_pos_feed(){ 38 | // this must be done by the caller 39 | //gs.setELSFactor(pitch); 40 | if(!pos_feeding){ 41 | 42 | //wait for the start to come around 43 | if(mc.waitForSync){ 44 | Serial.printf("Move: waiting for spindle sync target: %i distance: %i stopNeg: %d stopPos: %d nom: %d den: %d\n", 45 | mc.moveTargetSteps, 46 | mc.moveDistanceSteps, 47 | mc.stopNeg, mc.stopPos,gs.nom, gs.den); 48 | //gs.init_gear(encoder.getCount()); 49 | syncWaiting = true; 50 | pos_feeding = true; 51 | } 52 | else{ 53 | // this resets the "start" but i'm not sure if it works correctly 54 | // TODO: should warn that turning off sync will loose the "start" 55 | Serial.println("jog without spindle sync"); 56 | //gs.init_gear(encoder.getCount()); 57 | pos_feeding = true; 58 | } 59 | }else{ 60 | el.error("already started pos_feeding, can't do it again"); 61 | } 62 | } 63 | void init_hob_feed(){ 64 | el.error("this needs updated to work with genStepper.h"); 65 | //setHobbFactor(); 66 | if(!pos_feeding){ 67 | 68 | //wait for the start to come around 69 | if(mc.waitForSync){ 70 | Serial.println("waiting for spindle sync"); 71 | syncWaiting = true; 72 | pos_feeding = true; 73 | } 74 | else{ 75 | // this resets the "start" but i'm not sure if it works correctly 76 | // TODO: should warn that turning off sync will loose the "start" 77 | Serial.println("jog without spindle sync"); 78 | gs.init_gear(encoder.getCount()); 79 | pos_feeding = true; 80 | } 81 | }else{ 82 | el.error("already started pos_feeding, can't do it again"); 83 | } 84 | } 85 | 86 | 87 | 88 | // ensure we don't send steps after changing dir pin until the proper delay has expired 89 | void waitForDir(){ 90 | if(gs.zstepper.dir_has_changed){ 91 | while(gs.zstepper.dir_has_changed && ((gs.zstepper.dir_change_timer + 5) - esp_timer_get_time() > 0)){ 92 | gs.zstepper.dir_has_changed = false; 93 | if(!gs.zstepper.dir){ 94 | // reset stuff for dir changes guard against swapping when we just moved 95 | if(gs.mygear.last < encoder.pulse_counter){ 96 | gs.mygear.prev = gs.mygear.last; 97 | gs.mygear.last = gs.mygear.next; 98 | } 99 | 100 | }else{ 101 | // reset stuff for dir changes 102 | if(gs.mygear.last > encoder.pulse_counter){ 103 | gs.mygear.next = gs.mygear.last; 104 | gs.mygear.last = gs.mygear.prev; 105 | } 106 | } 107 | } 108 | } 109 | } 110 | 111 | 112 | // clean up vars on finish 113 | 114 | void finish_jog(){ 115 | if(rapiding){ 116 | mc.pitch = mc.oldPitch; 117 | rapiding = false; 118 | }else{ 119 | jogging = false; 120 | } 121 | pos_feeding = false; 122 | feeding_ccw = true; 123 | } 124 | 125 | 126 | /* 127 | this decides which direction to move the stepper and if it has reached the 128 | target position or if it has reached a virtual stop. it also decides when 129 | to calculate the next set of jumps (positions to step based on ratio/factor) 130 | 131 | this requires that everything is setup and ready to go: the vars that need to be set are: 132 | 133 | mc.moveDirection: the intended direction to feed 134 | if true: 135 | mc.stopNeg : the current tool position, this ensures if the spindle is reversed we will not jog beyond this point 136 | mc.stopPos : the target postion set from the "config" doc 137 | if false: 138 | swap Neg/Pos. Pos becomes the current position, Neg the target 139 | mc.syncMoveStart: if true this will ensure we start motion at spindle position 0 (the starting spindle angle) 140 | */ 141 | 142 | static int64_t pulse_counter = 0; 143 | 144 | void do_pos_feeding(){ 145 | 146 | // Sanity check 147 | // make sure we are not getting a huge jump in encoder values 148 | 149 | // only read this once for the whole loop 150 | // 151 | //int64_t pulse_counter = encoder.getCount(); 152 | pulse_counter = encoder.pulse_counter; 153 | 154 | if(pulse_counter > (gs.mygear.next + max_error) || pulse_counter < (gs.mygear.prev - max_error)){ 155 | sprintf(err,"Tool outside expected range. encPos: %lld next: %i pos %i ", 156 | pulse_counter, 157 | gs.mygear.next, 158 | gs.mygear.prev); 159 | el.addMsg(err); 160 | el.hasError = true; 161 | pos_feeding = false; 162 | return; 163 | } 164 | 165 | // Deal with direction changes 166 | // Encoder decrementing 167 | if(!encoder.dir){ // dir neg and not pausing for the direction change 168 | if(feeding_ccw && mc.moveDirection && gs.zstepper.dir){ 169 | gs.zstepper.setDir(false); 170 | }else if(feeding_ccw && !mc.moveDirection && !gs.zstepper.dir){ 171 | gs.zstepper.setDir(true); 172 | } 173 | 174 | // reverse spindle case 175 | else if(!feeding_ccw && !mc.moveDirection && gs.zstepper.dir){ 176 | gs.zstepper.setDir(false); 177 | }else if(!feeding_ccw && mc.moveDirection && !gs.zstepper.dir){ 178 | gs.zstepper.setDir(true); 179 | } 180 | waitForDir(); 181 | }else { 182 | 183 | // encoder incrementing 184 | if(feeding_ccw && mc.moveDirection && !gs.zstepper.dir){ 185 | gs.zstepper.setDir(true); 186 | }else if(feeding_ccw && !mc.moveDirection && gs.zstepper.dir){ 187 | gs.zstepper.setDir(false); 188 | } 189 | 190 | // reverse spindle case 191 | else if(!feeding_ccw && !mc.moveDirection && !gs.zstepper.dir){ 192 | gs.zstepper.setDir(true); 193 | }else if(!feeding_ccw && mc.moveDirection && gs.zstepper.dir){ 194 | gs.zstepper.setDir(false); 195 | } 196 | waitForDir(); 197 | } // done with direction changes 198 | 199 | 200 | // calculate jumps and delta 201 | 202 | 203 | if((pulse_counter == gs.mygear.next) || (pulse_counter== gs.mygear.prev)){ 204 | gs.step(); 205 | gs.mygear.calc_jumps(pulse_counter); 206 | //startCalcTask(); 207 | 208 | } 209 | 210 | // evaluate stops, no motion if motion would exceed stops 211 | 212 | if (mc.useStops && mc.moveDirection == true && gs.position >= mc.moveTargetSteps){ 213 | //ESP_LOGE(TAG,"reached target %d final position was: %d", mc.moveSyncTarget, gs.position); 214 | finish_jog(); 215 | return; 216 | } 217 | if(mc.useStops && mc.moveDirection == false && gs.position <= mc.moveTargetSteps){ 218 | //ESP_LOGE(TAG,"reached -target %d final position was: %d", mc.moveSyncTarget, gs.position); 219 | finish_jog(); 220 | return; 221 | } 222 | 223 | if(mc.useStops && (mc.moveTargetSteps < mc.stopNeg)){ 224 | el.addMsg("Tool past stopNeg: HALT"); 225 | el.hasError = true; 226 | finish_jog(); 227 | return; 228 | } 229 | 230 | if(mc.useStops && mc.moveTargetSteps > mc.stopPos){ 231 | el.addMsg("tool past stopPos: HALT"); 232 | el.hasError = true; 233 | 234 | // TODO: should we halt or just stop feeding? 235 | finish_jog(); 236 | return; 237 | } 238 | } 239 | 240 | 241 | // processMotion is called by the encoder class when it gets an update 242 | // 243 | void IRAM_ATTR processMotion(){ 244 | 245 | // check if we want to sync our start position 246 | if(syncWaiting && pos_feeding){ 247 | // faster to pass this count here or store it in do_pos_feeding? 248 | if(encoder.getCount() % encoder.start == 0){ 249 | syncWaiting = false; 250 | //gs.init_gear(encoder.getCount()); 251 | gs.mygear.calc_jumps(encoder.pulse_counter); 252 | do_pos_feeding(); 253 | } 254 | } 255 | else if(pos_feeding){ 256 | do_pos_feeding(); 257 | } 258 | 259 | 260 | if(el.hasError){ 261 | el.errorTask(); 262 | el.hasError = false; 263 | } 264 | 265 | } 266 | 267 | 268 | // gs.mygear.calc_jumps(pulse_counter); 269 | // this is not producing smooth motion above 400 RPM spindle speed 270 | void calcTask(void *ptr){ 271 | 272 | gs.mygear.calc_jumps(pulse_counter); 273 | 274 | vTaskDelete(NULL); 275 | } 276 | 277 | void startPinnedCalcTask(){ 278 | xTaskCreatePinnedToCore( 279 | calcTask, /* Task function. */ 280 | "calcTask", /* String with name of task. */ 281 | 10000, /* Stack size in words. */ 282 | NULL, /* Parameter passed as input of the task */ 283 | (configMAX_PRIORITIES -1 ), /* Priority of the task. */ 284 | NULL, 285 | 1); 286 | } 287 | 288 | void startCalcTask(){ 289 | xTaskCreate( 290 | calcTask, /* Task function. */ 291 | "calcTask", /* String with name of task. */ 292 | 10000, /* Stack size in words. */ 293 | NULL, /* Parameter passed as input of the task */ 294 | (configMAX_PRIORITIES -1 ), /* Priority of the task. */ 295 | NULL 296 | ); 297 | } 298 | 299 | // TOOD: is this needed? 300 | void init_motion(){ 301 | esp_timer_init(); 302 | //setFactor(); 303 | //gs.setELSFactor(pitch); 304 | } 305 | -------------------------------------------------------------------------------- /src/src/motion.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | #include "genStepper.h" 3 | #include "moveConfig.h" 4 | 5 | extern volatile bool feeding; 6 | 7 | 8 | // i think this reverses everything, usecase is unclear 9 | // should look at refactoring it out but unclear impact 10 | extern volatile bool feeding_ccw; 11 | 12 | void init_motion(void); 13 | void IRAM_ATTR calcDelta(void); 14 | void IRAM_ATTR processMotion(void); 15 | void start_rapid(double distance); 16 | void init_hob_feed(void); 17 | //void calcDelta(void *pvParaeters); 18 | void startCalcTask(void); 19 | 20 | void init_pos_feed(); 21 | 22 | 23 | -------------------------------------------------------------------------------- /src/src/moveConfig.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | #include 3 | 4 | // breaks tests 5 | //#include 6 | 7 | static const char* TAGmc = "Mc"; 8 | 9 | namespace MoveConfig{ 10 | 11 | struct State{ 12 | // was jog_mm 13 | static int32_t moveDistanceSteps ; 14 | static bool waitForSync ; 15 | // was z_feeding_direction 16 | static bool moveDirection ; 17 | 18 | static int stopPos ; 19 | static int stopNeg ; 20 | // spindle spinning CW or CCW 21 | static bool spindle_handedness ; 22 | static double pitch ; 23 | static double rapidPitch ; 24 | static double oldPitch ; 25 | //static bool syncMoveStart ; 26 | //static bool isAbs ; 27 | static bool useStops ; 28 | static int moveTargetSteps; 29 | 30 | // returns a bool to be used by stepper.setDir 31 | inline bool setStops(int32_t current_position){ 32 | useStops = true; 33 | /* 34 | if(!isAbs){ 35 | //moveSyncTarget = moveDistanceSteps; 36 | //ESP_LOGE(TAGmc,"Absolute move:\n"); 37 | }else { 38 | //ESP_LOGE(TAGmc,"Relative move: \n"); 39 | //moveSyncTarget = current_position + moveDistanceSteps; 40 | } 41 | */ 42 | if( moveDistanceSteps < 0){ 43 | 44 | moveDirection = false; 45 | stopNeg = moveDistanceSteps + current_position; 46 | moveTargetSteps = stopNeg; 47 | stopPos = current_position; 48 | //ESP_LOGE(TAGmc,"Stops:\n\t Distance: %ld stopNeg: %ld stopPos: %ld, moveDirection: %d\n",moveDistanceSteps, stopNeg, stopPos, moveDirection); 49 | printf("Stops:\n\t Distance: %i stopNeg: %i stopPos: %i, moveDirection: %d\n",moveDistanceSteps, stopNeg, stopPos, moveDirection); 50 | return false; 51 | } else{ 52 | moveDirection = true; 53 | stopPos = moveDistanceSteps + current_position; 54 | moveTargetSteps = stopPos; 55 | stopNeg = current_position; 56 | //ESP_LOGE(TAGmc,"Stops:\n\t Distance: %ld stopNeg: %ld stopPos: %ld, moveDirection: %d\n", moveDistanceSteps, stopNeg, stopPos, moveDirection); 57 | printf("Stops:\n\t Distance: %i stopNeg: %i stopPos: %i, moveDirection: %d\n",moveDistanceSteps, stopNeg, stopPos, moveDirection); 58 | 59 | return true; 60 | } 61 | } 62 | 63 | 64 | }; 65 | inline State init(){ 66 | State state; 67 | state.waitForSync = true; 68 | state.moveDirection = true; 69 | state.spindle_handedness = true; 70 | state.pitch = 0.1; 71 | state.rapidPitch = 0.1; 72 | state.oldPitch = state.pitch; 73 | //state.syncMoveStart = true; 74 | //state.isAbs = false; 75 | state.useStops = true; 76 | return state; 77 | } 78 | } 79 | -------------------------------------------------------------------------------- /src/src/myperfmon.c: -------------------------------------------------------------------------------- 1 | #include "myperfmon.h" 2 | 3 | #include "freertos/FreeRTOS.h" 4 | #include "freertos/task.h" 5 | #include "esp_freertos_hooks.h" 6 | //#include "sdkconfig.h" 7 | #include 8 | #include 9 | #include 10 | #include "esp_timer.h" 11 | #include "esp_log.h" 12 | #include "esp_sleep.h" 13 | #include 14 | 15 | static const char *TAG = "perfmon"; 16 | 17 | static uint64_t idle0Calls; 18 | static uint64_t idle1Calls; 19 | 20 | int8_t cpu0 = 0; 21 | int8_t cpu1 = 1; 22 | 23 | #if defined(CONFIG_ESP32_DEFAULT_CPU_FREQ_240) 24 | static const uint64_t MaxIdleCalls = 1855000; 25 | #elif defined(CONFIG_ESP32_DEFAULT_CPU_FREQ_160) 26 | static const uint64_t MaxIdleCalls = 1233100; 27 | #else 28 | #error "Unsupported CPU frequency" 29 | #endif 30 | 31 | // Table with dedicated performance counters 32 | // TODO: figure out how to use perfmon 33 | static uint32_t pm_check_table[] = { 34 | XTPERF_CNT_CYCLES, XTPERF_MASK_CYCLES, // total cycles 35 | XTPERF_CNT_INSN, XTPERF_MASK_INSN_ALL, // total instructions 36 | XTPERF_CNT_D_LOAD_U1, XTPERF_MASK_D_LOAD_LOCAL_MEM, // Mem read 37 | XTPERF_CNT_D_STORE_U1, XTPERF_MASK_D_STORE_LOCAL_MEM, // Mem write 38 | XTPERF_CNT_BUBBLES, XTPERF_MASK_BUBBLES_ALL &(~XTPERF_MASK_BUBBLES_R_HOLD_REG_DEP), // wait for other reasons 39 | XTPERF_CNT_BUBBLES, XTPERF_MASK_BUBBLES_R_HOLD_REG_DEP, // Wait for register dependency 40 | XTPERF_CNT_OVERFLOW, XTPERF_MASK_OVERFLOW, // Last test cycle 41 | }; 42 | // 43 | 44 | #define TOTAL_CALL_AMOUNT 200 45 | #define PERFMON_TRACELEVEL -1 // -1 - will ignore trace level 46 | 47 | bool exec_test_function(){ 48 | int i = 1+1; 49 | return true; 50 | } 51 | 52 | void pukeStats(){ 53 | // 54 | ESP_LOGI(TAG, "Start"); 55 | ESP_LOGI(TAG, "Start test with printing all available statistic"); 56 | xtensa_perfmon_config_t pm_config = {}; 57 | pm_config.counters_size = sizeof(xtensa_perfmon_select_mask_all) / sizeof(uint32_t) / 2; 58 | pm_config.select_mask = xtensa_perfmon_select_mask_all; 59 | pm_config.repeat_count = TOTAL_CALL_AMOUNT; 60 | pm_config.max_deviation = 1; 61 | pm_config.call_function = exec_test_function; 62 | pm_config.callback = xtensa_perfmon_view_cb; 63 | pm_config.callback_params = stdout; 64 | pm_config.tracelevel = PERFMON_TRACELEVEL; 65 | xtensa_perfmon_exec(&pm_config); 66 | 67 | /* 68 | ESP_LOGI(TAG, "Start test with user defined statistic"); 69 | pm_config.counters_size = sizeof(pm_check_table) / sizeof(uint32_t) / 2; 70 | pm_config.select_mask = pm_check_table; 71 | pm_config.repeat_count = TOTAL_CALL_AMOUNT; 72 | pm_config.max_deviation = 1; 73 | pm_config.call_function = exec_test_function; 74 | pm_config.callback = xtensa_perfmon_view_cb; 75 | pm_config.callback_params = stdout; 76 | pm_config.tracelevel = PERFMON_TRACELEVEL; 77 | 78 | xtensa_perfmon_exec(&pm_config); 79 | */ 80 | 81 | ESP_LOGI(TAG, "The End"); 82 | // 83 | } 84 | 85 | static bool idle_task_0() 86 | { 87 | idle0Calls += 1; 88 | return false; 89 | } 90 | 91 | static bool idle_task_1() 92 | { 93 | idle1Calls += 1; 94 | return false; 95 | } 96 | 97 | static void perfmon_task(void *args) 98 | { 99 | while (1) 100 | { 101 | float idle0 = idle0Calls; 102 | float idle1 = idle1Calls; 103 | idle0Calls = 0; 104 | idle1Calls = 0; 105 | 106 | cpu0 = 100.f - idle0 / MaxIdleCalls * 100.f; 107 | cpu1 = 100.f - idle1 / MaxIdleCalls * 100.f; 108 | 109 | /* 110 | ESP_LOGI(TAG, "Core 0 at %d%%", cpu0); 111 | ESP_LOGI(TAG, "Core 1 at %d%%", cpu1); 112 | */ 113 | //pukeStats(); 114 | // TODO configurable delay 115 | vTaskDelay(2000 / portTICK_PERIOD_MS); 116 | } 117 | vTaskDelete(NULL); 118 | } 119 | 120 | esp_err_t perfmon_start() 121 | { 122 | ESP_ERROR_CHECK(esp_register_freertos_idle_hook_for_cpu(idle_task_0, 0)); 123 | ESP_ERROR_CHECK(esp_register_freertos_idle_hook_for_cpu(idle_task_1, 1)); 124 | // TODO calculate optimal stack size 125 | xTaskCreate(perfmon_task, "perfmon", 2048, NULL, 1, NULL); 126 | return ESP_OK; 127 | } 128 | -------------------------------------------------------------------------------- /src/src/myperfmon.h: -------------------------------------------------------------------------------- 1 | #ifndef COMPONENTS_PERFMON_INCLUDE_PERFMON_H_ 2 | #define COMPONENTS_PERFMON_INCLUDE_PERFMON_H_ 3 | 4 | 5 | #ifdef __cplusplus 6 | extern "C" { 7 | #endif 8 | 9 | #include 10 | 11 | extern int8_t cpu0; 12 | extern int8_t cpu1; 13 | 14 | esp_err_t perfmon_start(); 15 | 16 | #ifdef __cplusplus 17 | } 18 | #endif 19 | 20 | #endif /* COMPONENTS_PERFMON_INCLUDE_PERFMON_H_ */ 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | -------------------------------------------------------------------------------- /src/src/neotimer.cpp: -------------------------------------------------------------------------------- 1 | #include "neotimer.h" 2 | 3 | //Default constructor 4 | Neotimer::Neotimer(){ 5 | this->_timer.time = 1000; //Default 1 second interval if not specified 6 | } 7 | 8 | Neotimer::Neotimer(unsigned long _t){ 9 | this->_timer.time = _t; 10 | } 11 | 12 | //Default destructor 13 | Neotimer::~Neotimer(){ 14 | 15 | } 16 | 17 | //Initializations 18 | void Neotimer::init(){ 19 | this->_waiting = false; 20 | } 21 | 22 | /* 23 | * Repeats a timer x times 24 | * Useful to execute a task periodically. 25 | * Usage: 26 | * if(timer.repeat(10)){ 27 | * do something 10 times, every second (default) 28 | * } 29 | */ 30 | boolean Neotimer::repeat(int times){ 31 | if(times != NEOTIMER_UNLIMITED){ 32 | // First repeat 33 | if(this->repetitions == NEOTIMER_UNLIMITED){ 34 | this->repetitions = times; 35 | } 36 | // Stop 37 | if(this->repetitions == 0){ 38 | return false; 39 | } 40 | 41 | if(this->repeat()){ 42 | this->repetitions--; 43 | return true; 44 | } 45 | return false; 46 | } 47 | return this->repeat(); 48 | } 49 | 50 | /* 51 | * Repeats a timer x times with a defined period 52 | * Useful to execute a task periodically. 53 | * Usage: 54 | * if(timer.repeat(10,5000)){ 55 | * do something 10 times, every 5 seconds 56 | * } 57 | */ 58 | boolean Neotimer::repeat(int times, unsigned long _t){ 59 | this->_timer.time = _t; 60 | return this->repeat(times); 61 | } 62 | 63 | /* 64 | * Repeats a timer indefinetely 65 | * Useful to execute a task periodically. 66 | * Usage: 67 | * if(timer.repeat()){ 68 | * do something indefinetely, every second (default) 69 | * } 70 | */ 71 | boolean Neotimer::repeat(){ 72 | if(this->done()){ 73 | this->reset(); 74 | return true; 75 | } 76 | if(!this->_timer.started){ 77 | this->_timer.last = millis(); 78 | this->_timer.started = true; 79 | this->_waiting = true; 80 | } 81 | return false; 82 | } 83 | 84 | void Neotimer::repeatReset(){ 85 | this->repetitions = -1; 86 | } 87 | 88 | /* 89 | * Checks if timer has finished 90 | * Returns true if it finished 91 | */ 92 | boolean Neotimer::done(){ 93 | if(!this->_timer.started) return false; 94 | if( (millis()-this->_timer.last) >= this->_timer.time){ 95 | this->_timer.done = true; 96 | this->_waiting = false; 97 | return true; 98 | } 99 | return false; 100 | } 101 | 102 | /* 103 | * Sets a timer preset 104 | */ 105 | void Neotimer::set(unsigned long t){ 106 | this->_timer.time = t; 107 | } 108 | 109 | /* 110 | * Gets the timer preset 111 | */ 112 | unsigned long Neotimer::get(){ 113 | return this->_timer.time; 114 | } 115 | 116 | /* 117 | * Returns the debounced value of signal 118 | * This is very useful to avoid "bouncing" 119 | * of electromechanical signals 120 | */ 121 | boolean Neotimer::debounce(boolean signal){ 122 | if(this->done() && signal){ 123 | this->start(); 124 | return true; 125 | } 126 | return false; 127 | } 128 | 129 | /* 130 | * Resets a timer 131 | */ 132 | void Neotimer::reset(){ 133 | this->stop(); 134 | this->_timer.last = millis(); 135 | this->_timer.done = false; 136 | } 137 | 138 | /* 139 | * Start a timer 140 | */ 141 | void Neotimer::start(){ 142 | this->reset(); 143 | this->_timer.started = true; 144 | this->_waiting = true; 145 | } 146 | 147 | /* 148 | * Stops a timer 149 | */ 150 | unsigned long Neotimer::stop(){ 151 | this->_timer.started = false; 152 | this->_waiting = false; 153 | return this->getEllapsed(); 154 | } 155 | 156 | /* 157 | * Gets ellapsed time 158 | */ 159 | unsigned long Neotimer::getEllapsed(){ 160 | return millis()-this->_timer.last; 161 | } 162 | 163 | /* 164 | * Continues a stopped timer 165 | */ 166 | void Neotimer::restart(){ 167 | if(!this->done()){ 168 | this->_timer.started = true; 169 | this->_waiting = true; 170 | } 171 | } 172 | 173 | /* 174 | * Indicates if the timer is active 175 | * but has not yet finished. 176 | */ 177 | boolean Neotimer::waiting(){ 178 | return (this->_timer.started && !this->done()) ? true : false; 179 | } 180 | 181 | boolean Neotimer::started(){ 182 | return this->_timer.started; 183 | } -------------------------------------------------------------------------------- /src/src/neotimer.h: -------------------------------------------------------------------------------- 1 | #ifndef NEOTIMER_H 2 | #define NEOTIMER_H 3 | 4 | #define NEOTIMER_INDEFINITE -1 5 | #define NEOTIMER_UNLIMITED -1 6 | 7 | 8 | #include 9 | 10 | class Neotimer{ 11 | public: 12 | //Methods 13 | Neotimer(); 14 | Neotimer(unsigned long _t); //Constructor 15 | ~Neotimer(); //Destructor 16 | 17 | void init(); //Initializations 18 | boolean done(); //Indicates time has elapsed 19 | boolean repeat(int times); 20 | boolean repeat(int times, unsigned long _t); 21 | boolean repeat(); 22 | void repeatReset(); 23 | boolean waiting(); // Indicates timer is started but not finished 24 | boolean started(); // Indicates timer has started 25 | void start(); //Starts a timer 26 | unsigned long stop(); //Stops a timer and returns elapsed time 27 | unsigned long getEllapsed(); // Gets the ellapsed time 28 | void restart(); 29 | void reset(); //Resets timer to zero 30 | void set(unsigned long t); 31 | unsigned long get(); 32 | boolean debounce(boolean signal); 33 | int repetitions = NEOTIMER_UNLIMITED; 34 | 35 | private: 36 | 37 | struct myTimer{ 38 | unsigned long time; 39 | unsigned long last; 40 | boolean done; 41 | boolean started; 42 | }; 43 | 44 | struct myTimer _timer; 45 | boolean _waiting; 46 | }; 47 | #endif -------------------------------------------------------------------------------- /src/src/pcntEncoder.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | ESP32Encoder pencoder; 4 | 5 | void init(){ 6 | // Handle pullups 7 | //pencoder.attachFullQuad(EA,EB); 8 | } 9 | -------------------------------------------------------------------------------- /src/src/pcntEncoder.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include 4 | -------------------------------------------------------------------------------- /src/src/rmtStepper.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | 4 | 5 | // this seems like a horrible hack 6 | #ifdef UNIT_TEST 7 | 8 | // if unit testing.... 9 | // don't include, this will get included from 'mocks.h' 10 | 11 | #else 12 | 13 | #include "config.h" 14 | #include 15 | #include 16 | 17 | 18 | namespace rmtStepper { 19 | struct Config{ 20 | gpio_num_t stepPin; 21 | gpio_num_t dirPin; 22 | rmt_channel_t channel; 23 | bool invert_step_pin = false; 24 | }; 25 | 26 | 27 | 28 | struct State { 29 | volatile bool dir = true; 30 | int pos = 0; 31 | Config config; 32 | rmt_item32_t items[2]; 33 | rmt_config_t rconfig; 34 | int64_t dir_change_timer; 35 | bool dir_has_changed = false; 36 | 37 | void step(){ 38 | RMT.conf_ch[RMT_CHANNEL_0].conf1.mem_rd_rst = 1; 39 | RMT.conf_ch[RMT_CHANNEL_0].conf1.tx_start = 1; 40 | if(dir){ 41 | pos++; 42 | }else{ 43 | pos--; 44 | } 45 | } 46 | bool setDir(bool newdir){ 47 | //ESP_LOGE("thing","setDir called current dir: %d arg dir: %d",dir,newdir); 48 | bool olddir = dir; 49 | if(dir != newdir){ 50 | // XOR the dir for the inversion bool 51 | dir_has_changed = true; 52 | 53 | // TODO need to be able to invert 54 | //digitalWrite(config.dirPin, newdir ^ config.invert_step_pin); 55 | digitalWrite(config.dirPin, newdir); 56 | dir = newdir; 57 | dir_change_timer = esp_timer_get_time(); 58 | } 59 | return olddir == newdir; 60 | } 61 | 62 | bool setDirNow(bool newdir){ 63 | digitalWrite(config.dirPin, newdir); 64 | dir = newdir; 65 | return dir; 66 | } 67 | 68 | void init(){ 69 | rconfig.rmt_mode = RMT_MODE_TX; 70 | rconfig.channel = config.channel; // 71 | rconfig.gpio_num = config.stepPin; 72 | rconfig.mem_block_num = 2; //??? 73 | rconfig.tx_config.loop_en = false; 74 | rconfig.tx_config.carrier_en = false; 75 | rconfig.tx_config.carrier_freq_hz = 0; 76 | rconfig.tx_config.idle_output_en = true; 77 | rconfig.tx_config.idle_level = RMT_IDLE_LEVEL_LOW; 78 | rconfig.tx_config.carrier_level = RMT_CARRIER_LEVEL_LOW; 79 | rconfig.clk_div = 20; //// 80MHx / 80 = 1MHz 0r 1uS per count 80 | rconfig.tx_config.carrier_duty_percent = 50; 81 | rmt_set_source_clk(rconfig.channel, RMT_BASECLK_APB); 82 | rconfig.tx_config.idle_level = config.invert_step_pin ? RMT_IDLE_LEVEL_HIGH : RMT_IDLE_LEVEL_LOW; 83 | 84 | items[0].duration0 = 1; 85 | items[0].duration1 = 4 * 3; // this is a setting pulse_microseconds->get(); 86 | 87 | items[1].duration0 = 0; 88 | items[1].duration1 = 0; 89 | items[0].level0 = rconfig.tx_config.idle_level; 90 | items[0].level1 = !rconfig.tx_config.idle_level; 91 | 92 | rmt_config(&rconfig); 93 | rmt_fill_tx_items(rconfig.channel, &items[0], rconfig.mem_block_num, 0); 94 | digitalWrite(config.dirPin,dir); 95 | } 96 | }; 97 | } 98 | #endif 99 | -------------------------------------------------------------------------------- /src/src/state.cpp: -------------------------------------------------------------------------------- 1 | #include "state.h" 2 | 3 | #include "genStepper.h" 4 | #include "moveConfig.h" 5 | //Initialize the starting memory. 6 | //TODO: move this into a class constructor 7 | #include "ArduinoJson.h" 8 | //Initialize the starting memory. 9 | 10 | // TODO: can this be automagical somehow? 11 | const char* vsn = "0.0.3"; 12 | 13 | //common variables used by multipe things 14 | volatile int rpm = 0; 15 | double mmPerStep = 0; 16 | int32_t stepsPerMM = 0; 17 | int32_t relativePosition = 0; 18 | int32_t absolutePosition = 0; 19 | bool sendDebug = true; 20 | 21 | 22 | //State Machine stuff 23 | bool syncStart = true; 24 | bool syncWaiting = false; 25 | volatile bool jogging = false; 26 | volatile bool rapiding = false; 27 | 28 | 29 | RunMode run_mode = RunMode::STARTUP; 30 | 31 | 32 | GenStepper::Config gconf = { 33 | 0, 34 | "Z", 35 | LEADSCREW_LEAD, // lead screw pitch 36 | ENCODER_RESOLUTION, // spindle enc resolution 37 | Z_NATIVE_STEPS_PER_REV, // native steps 38 | Z_MICROSTEPPING, // microsteps 39 | (Z_NATIVE_STEPS_PER_REV * Z_MICROSTEPPING) // motorsteps 40 | }; 41 | GenStepper::State gs = GenStepper::init("Z",el,gconf); 42 | MoveConfig::State mc = MoveConfig::init(); 43 | // json docs 44 | 45 | // config stateDoc 46 | StaticJsonDocument<1000> stateDoc; 47 | 48 | // items to store in NV ram/EEPROM 49 | StaticJsonDocument<1000> nvConfigDoc; 50 | 51 | // Used for msgs from UI 52 | StaticJsonDocument<1000> inDoc; 53 | 54 | // used to send status to UI 55 | StaticJsonDocument<600> statusDoc; 56 | 57 | // Used to log to UI 58 | StaticJsonDocument<5000> logDoc; 59 | 60 | // used for debugging, to slim down status doc 61 | StaticJsonDocument<500> debugStatusDoc; 62 | 63 | StaticJsonDocument<100> pongDoc; 64 | char pongBuf[100]; 65 | int pong_len = serializeMsgPack(pongDoc,pongBuf); 66 | 67 | -------------------------------------------------------------------------------- /src/src/state.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | //State that's common to multiple contexts. 3 | //TODO: (Chris) Eventually move this to a class, perhaps the state machine. Then we don't have to 4 | // extern all these things to make the linker happy, and each object can guarantee nothing else 5 | // is writing to this memory when it shouldn't be (makes future expansion easier) 6 | //TODO: identify which of these belong to other objects and make those objects "own" these 7 | #include "Encoder.h" 8 | #include "Controls.h" 9 | #include "genStepper.h" 10 | #include "moveConfig.h" 11 | 12 | // TODO: can this be automagical somehow? 13 | extern const char* vsn; 14 | 15 | #include "ArduinoJson.h" 16 | 17 | //common variables used by multipe things 18 | extern volatile int rpm; 19 | extern double mmPerStep; 20 | extern int32_t stepsPerMM; 21 | extern int32_t relativePosition; 22 | extern int32_t absolutePosition; 23 | extern bool sendDebug; 24 | 25 | 26 | extern GenStepper::State gs; 27 | extern MoveConfig::State mc; 28 | 29 | //State Machine stuff 30 | extern bool syncStart; 31 | extern bool syncWaiting; 32 | extern volatile bool jogging; 33 | extern volatile bool rapiding; 34 | 35 | extern RunMode run_mode; 36 | 37 | extern double lead_screw_pitch; 38 | 39 | 40 | // config stateDoc 41 | extern StaticJsonDocument<1000> stateDoc; 42 | 43 | // items to store in NV ram/EEPROM 44 | extern StaticJsonDocument<1000> nvConfigDoc; 45 | 46 | // Used for msgs from UI 47 | extern StaticJsonDocument<1000> inDoc; 48 | 49 | // used to send status to UI 50 | extern StaticJsonDocument<600> statusDoc; 51 | 52 | // Used to log to UI 53 | extern StaticJsonDocument<5000> logDoc; 54 | 55 | // used for debugging, to slim down status doc 56 | extern StaticJsonDocument<500> debugStatusDoc; 57 | 58 | // for pong 59 | extern StaticJsonDocument<100> pingDoc; 60 | extern char pongBuf[100]; 61 | extern int pong_len; 62 | 63 | 64 | -------------------------------------------------------------------------------- /src/src/util.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include "util.h" 3 | #include "config.h" 4 | 5 | 6 | 7 | 8 | 9 | 10 | const char* DISPLAY_MODE [] = 11 | { 12 | "Startup", 13 | "Configure", 14 | "Status", 15 | "Ready", 16 | "Feeding", 17 | "Slave Ready", 18 | "Debug Ready" 19 | }; 20 | 21 | 22 | /* i hate C 23 | 24 | void menu_next(int *index, (char**) ary){ 25 | *index++; 26 | int size = sizeof(ary) / sizeof ary[0]; 27 | if(*index > size){ 28 | *index = 0; 29 | } 30 | } 31 | void menu_prev(int *index, const char* ary){ 32 | *index--; 33 | int size = sizeof(ary) / sizeof ary[0]; 34 | if(*index < size){ 35 | *index = size; 36 | } 37 | } 38 | */ 39 | -------------------------------------------------------------------------------- /src/src/util.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | #ifdef HAS_BUTTONS 3 | #include 4 | #endif 5 | 6 | namespace Log{ 7 | class Msg; 8 | }; 9 | 10 | enum display_mode_t { 11 | STARTUP, 12 | CONFIGURE, 13 | DSTATUS, 14 | READY, 15 | FEEDING, 16 | SLAVE_READY, 17 | DEBUG_READY 18 | } ; 19 | 20 | enum class RunMode{ 21 | STARTUP, 22 | SLAVE_READY, 23 | SLAVE_JOG_READY, // 2 24 | DEBUG_READY, //3 25 | RUNNING, // 4 Any mode where we are actually moving. 26 | BounceIdle, // 5 27 | BounceMove, // 6 28 | BounceRapid, //7 29 | BounceFinish, //8 30 | HOB_READY, // 9 31 | HOB_RUN, // 10 32 | HOB_STOP, // 11 33 | DIVIDER_READY, //12 34 | DIVIDER_RUN, //13 35 | FEED_READY, // 14 36 | THREAD_READY // 15 37 | }; 38 | 39 | enum feed_mode_t { 40 | RAPID_FEED, 41 | FEED, 42 | THREAD 43 | } ; 44 | 45 | 46 | #define zPos 1 47 | #define zNeg 0 48 | 49 | #ifdef HAS_BUTTONS 50 | // button data definition 51 | 52 | struct Bd{ 53 | uint8_t pin; 54 | const char* name; 55 | bool changed; 56 | bool change_read; 57 | bool state; 58 | Bounce *deb; 59 | uint8_t idx; 60 | }; 61 | 62 | #endif 63 | -------------------------------------------------------------------------------- /src/src/web.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include "web.h" 3 | #include 4 | #include 5 | #include 6 | #include "config.h" 7 | #include "log.h" 8 | #include "Encoder.h" 9 | #include "state.h" 10 | #include "Stepper.h" 11 | #include "BounceMode.h" 12 | #include "Machine.h" 13 | #include "Controls.h" 14 | #include "SlaveMode.h" 15 | #include "myperfmon.h" 16 | #include "display.h" 17 | #include "DebugMode.h" 18 | #include "Stepper.h" 19 | #include "motion.h" 20 | #include "hob.h" 21 | #include "moveConfig.h" 22 | #include 23 | #include "led.h" 24 | 25 | 26 | #include "web.h" 27 | 28 | // To force delete the nvconfig 29 | #define KILLNV 0 30 | 31 | bool web = true; 32 | static const char* TAGweb = "Mc"; 33 | 34 | 35 | // buffer for msgpack 36 | char outBuffer[6000]; 37 | 38 | size_t serialize_len = 0; 39 | 40 | // stores websocket data from asyncWebServer that gets fed to arduinoJSON 41 | String wsData; 42 | 43 | // sends updates (statusDoc) to UI every interval 44 | Neotimer update_timer = Neotimer(1000); 45 | Neotimer ota_timer = Neotimer(200); 46 | 47 | // TOOD: consider configs from config.h to update this stuff 48 | AsyncWebServer server(80); 49 | AsyncWebSocket ws("/els"); 50 | AsyncWebSocketClient *globalClient = NULL; 51 | 52 | // This is a bit like a ping counter, increments each time a new status is sent to the UI 53 | uint8_t statusCounter = 0; 54 | 55 | // I htink this is sent from the UI and used to set the absolute target postion, in the Doc it is "ja" 56 | double jogAbs = 0; 57 | 58 | void saveNvConfigDoc() 59 | { 60 | EepromStream eepromStream(0, 512); 61 | nvConfigDoc["motor_steps"] = nvConfigDoc["native_steps"].as() * nvConfigDoc["microsteps"].as(); 62 | serializeJson(nvConfigDoc, eepromStream); 63 | eepromStream.flush(); 64 | Serial.print(" Saving Doc: "); 65 | serializeJson(nvConfigDoc,Serial); 66 | loadNvConfigDoc(); 67 | sendDoc(nvConfigDoc); 68 | } 69 | 70 | void initNvConfigDoc() 71 | { 72 | nvConfigDoc.clear(); 73 | // this flag says we've updated from the default 74 | nvConfigDoc["i"] = 1; 75 | 76 | // the config 77 | nvConfigDoc["lead_screw_pitch"] = LEADSCREW_LEAD; 78 | nvConfigDoc["spindle_encoder_resolution"] = ENCODER_RESOLUTION; 79 | nvConfigDoc["microsteps"] = Z_MICROSTEPPING; 80 | nvConfigDoc["EA"] = EA; 81 | nvConfigDoc["EB"] = EB; 82 | nvConfigDoc["ZP"] = gs.zstepper.config.stepPin; 83 | nvConfigDoc["ZD"] = gs.zstepper.config.dirPin; 84 | nvConfigDoc["motor_steps"] = Z_MICROSTEPPING * Z_NATIVE_STEPS_PER_REV; 85 | nvConfigDoc["native_steps"] = Z_NATIVE_STEPS_PER_REV; 86 | 87 | // the communication version, used to detect UI compatability 88 | nvConfigDoc["vsn"] = vsn; 89 | 90 | // TODO list of things to add 91 | /* 92 | 93 | UI_update_rate 94 | last_pitch ? do I want to do that? 95 | motor acceleration 96 | motor max_speed 97 | 98 | */ 99 | // nvConfigDoc[""] = ; 100 | 101 | saveNvConfigDoc(); 102 | } 103 | 104 | 105 | 106 | void loadNvConfigDoc() 107 | { 108 | EepromStream eepromStream(0, 512); 109 | deserializeJson(nvConfigDoc, eepromStream); 110 | if (KILLNV == 1|| !nvConfigDoc["i"] ){ 111 | Serial.print("Doc!? "); 112 | Serial.println((int)nvConfigDoc["i"]); 113 | el.error("no config found this is bad"); 114 | serializeJsonPretty(nvConfigDoc, Serial); 115 | } 116 | else 117 | { 118 | 119 | if(nvConfigDoc.containsKey("lead_screw_pitch")){ 120 | lead_screw_pitch = nvConfigDoc["lead_screw_pitch"].as(); 121 | }else{ 122 | Serial.println("key missing: lead"); 123 | } 124 | 125 | 126 | if(nvConfigDoc.containsKey("native_steps")){ 127 | native_steps = nvConfigDoc["native_steps"].as(); 128 | }else{ 129 | Serial.println("key missing: nat step"); 130 | } 131 | 132 | if(nvConfigDoc.containsKey("microsteps")){ 133 | microsteps = nvConfigDoc["microsteps"].as(); 134 | }else{ 135 | Serial.println("key missing: microstesp"); 136 | } 137 | 138 | if(nvConfigDoc.containsKey("spindle_encoder_resolution")){ 139 | spindle_encoder_resolution = nvConfigDoc["spindle_encoder_resolution"].as(); 140 | }else{ 141 | Serial.println("key missing: enc"); 142 | } 143 | 144 | motor_steps = native_steps * microsteps; 145 | nvConfigDoc["motor_steps"] = motor_steps; 146 | 147 | /* TODO: all of these shouldn't be global and need to switch to gs.c 148 | motor_steps = nvConfigDoc["motor_steps"]; 149 | native_steps = nvConfigDoc["native_steps"]; 150 | microsteps = nvConfigDoc["microsteps"]; 151 | spindle_encoder_resolution = nvConfigDoc["spindle_encoder_resolution"]; 152 | */ 153 | Serial.printf("Loaded Configuration com version %s lead screw pitch: %f\n", vsn, lead_screw_pitch); 154 | init_machine(); 155 | // setFactor(); 156 | gs.c.lead_screw_pitch = lead_screw_pitch; 157 | gs.c.motor_steps = motor_steps; 158 | gs.c.microsteps = microsteps; 159 | gs.c.spindle_encoder_resolution = spindle_encoder_resolution; 160 | Serial.print("Loaded this NvConfig doc"); 161 | serializeJsonPretty(nvConfigDoc, Serial); 162 | if(!gs.setELSFactor(mc.pitch,true)){ 163 | Serial.println("Something wrong with this NvConfig!!!!!"); 164 | } 165 | } 166 | } 167 | 168 | void updateStatusDoc() 169 | { 170 | // types the message as a status update for the UI 171 | statusDoc["t"] = "status"; 172 | 173 | // Currently used for the UI DRO display, 174 | // defined in util.h and helps UI figure out what to display 175 | statusDoc["m"] = (int)run_mode; 176 | // the position in steps 177 | statusDoc["p"] = gs.position; 178 | 179 | // encoder postion in cpr pulses 180 | statusDoc["encoderPos"] = encoder.getCount(); 181 | 182 | // I think this is used for aboslute movements 183 | // TODO: We should convert to steps in the UI and not have to do the conversion in the controller 184 | statusDoc["targetSteps"] = mc.moveDistanceSteps; 185 | // bool for constant run mode, TODO: bad name though 186 | //statusDoc["feeding"] = feeding; 187 | // bools for sync movements, TODO: bad name 188 | statusDoc["jogging"] = jogging; 189 | // bool for rapid sync movement TODO: bad name 190 | statusDoc["rap"] = rapiding; 191 | // flag for bouncing mode 192 | statusDoc["bf"] = bouncing; 193 | // main bool to turn movement on/off 194 | statusDoc["pos_feed"] = pos_feeding; 195 | 196 | // Wait for the spindle/ncoder "0" position 197 | // this acts like a thread dial 198 | statusDoc["sw"] = syncWaiting; 199 | // generated in the encoder and displayed in the UI 200 | // TODO: consider making the smoothing configurable or done in the browser 201 | statusDoc["rpm"] = rpm; 202 | 203 | // the virtual stop in the Z + direction, used to calculate "distance to go" in the UI 204 | statusDoc["sp"] = mc.stopPos; 205 | // the stop in the Z - direction 206 | statusDoc["sn"] = mc.stopNeg; 207 | statusDoc["r"] = WiFi.RSSI(); 208 | 209 | // this is used by "Distance to Go" in the UI to figure out the direction 210 | statusDoc["fd"] = mc.moveDirection; 211 | sendStatus(); 212 | } 213 | 214 | void updateDebugStatusDoc() 215 | { 216 | // types as a debug status msg 217 | debugStatusDoc["t"] = "dbg_st"; 218 | // intended feeding "handiness" CCW or CW 219 | // so if the spindle is rotating CW, and the intension is to feed in the Z- direction this should be false 220 | // but this somewhat depends on the setup 221 | 222 | 223 | // This is the number of encoder pulses needed before the next stepper pulse 224 | // TODO: make this optional and move to a "debug" doc 225 | debugStatusDoc["delta"] = delta; 226 | // this doesn't appear to be used now, but... 227 | debugStatusDoc["targetPos"] = mc.moveTargetSteps; 228 | // for cpu stats 229 | // TODO: move this to a debug doc 230 | debugStatusDoc["c0"] = cpu0; 231 | debugStatusDoc["c1"] = cpu1; 232 | // this is incremented every status update 233 | debugStatusDoc["c"] = statusCounter++; 234 | debugStatusDoc["h"] = ESP.getFreeHeap(); 235 | debugStatusDoc["ha"] = ESP.getHeapSize(); 236 | debugStatusDoc["cc"] = ws.count(); 237 | // average time of encoder ISR 238 | debugStatusDoc["at"] = avg_times; 239 | 240 | /* 241 | esp_chip_info_t* out_info = ESP.get_chip_info(); 242 | make object .... parse this struct 243 | debugStatusDoc["chip"] = chipInfo; 244 | */ 245 | } 246 | 247 | void updateStateDoc() 248 | { 249 | stateDoc["t"] = "state"; 250 | 251 | // the pitch for the sync move calculation in MM 252 | stateDoc["pitch"] = mc.pitch; 253 | // the pitch for sync rapid moves 254 | stateDoc["rapid"] = mc.rapidPitch; 255 | 256 | // the run mode 257 | stateDoc["m"] = (int)run_mode; 258 | // TODO: not used but this shold be used instead of jog_mm and the UI should do the conversion 259 | stateDoc["js"] = mc.moveDistanceSteps; 260 | // this is the distance to jog in mm 261 | // this sets the desired "handedness" CW or CCW 262 | stateDoc["f"] = mc.moveDirection; 263 | // this is the target postion for sync absolute movements 264 | stateDoc["ja"] = jogAbs; 265 | // flag to wait for encocer "0" position 266 | stateDoc["s"] = syncStart; 267 | // TODO: add angle for angle readout in UI 268 | 269 | 270 | sendState(); 271 | } 272 | 273 | void setRunMode(int mode) 274 | { 275 | switch (mode) 276 | { 277 | case (int)RunMode::DEBUG_READY: 278 | // NEed to be able to stop what is currently running 279 | bounce_yasm.next(debugState); 280 | break; 281 | case (int)RunMode::SLAVE_JOG_READY: 282 | bounce_yasm.next(slaveJogReadyState); 283 | break; 284 | case (int)RunMode::SLAVE_READY: 285 | bounce_yasm.next(SlaveModeReadyState); 286 | break; 287 | case (int)RunMode::FEED_READY: 288 | bounce_yasm.next(FeedModeReadyState); 289 | break; 290 | case (int)RunMode::HOB_READY: 291 | // hob_yasm.next(HobReadyState); 292 | HobReadyState(); 293 | break; 294 | default: 295 | bounce_yasm.next(startupState); 296 | break; 297 | } 298 | } 299 | 300 | void sendDoc(const JsonDocument &doc) 301 | { 302 | serialize_len = serializeMsgPack(doc, outBuffer); 303 | // TODO: debug flag? 304 | //if(globalClient->canSend()){ 305 | //ws.queueisFull(); 306 | if(ws.availableForWriteAll()){ 307 | ws.binaryAll(outBuffer, serialize_len); 308 | }else{ 309 | Serial.println("\n\tWS not available"); 310 | } 311 | //}else{ 312 | //ESP_LOGE(TAGweb,"can't send doc"); 313 | //} 314 | 315 | } 316 | 317 | void sendState() 318 | { 319 | sendDoc(stateDoc); 320 | } 321 | 322 | void sendLogP(Log::Msg *msg) 323 | { 324 | logDoc["msg"] = msg->buf; 325 | logDoc["level"] = (int)msg->level; 326 | logDoc["t"] = "log"; 327 | sendDoc(logDoc); 328 | } 329 | 330 | void sendStatus() 331 | { 332 | sendDoc(statusDoc); 333 | if (sendDebug) 334 | { 335 | sendDoc(debugStatusDoc); 336 | } 337 | } 338 | 339 | void sendNvConfigDoc() 340 | { 341 | nvConfigDoc["t"] = "nvConfig"; 342 | sendDoc(nvConfigDoc); 343 | } 344 | 345 | void handleJogAbs() 346 | { 347 | 348 | el.error("handleJogAbs needs full refactor to work with feeding_ccw and steps vs mm"); 349 | /* 350 | JsonObject config = inDoc["config"]; 351 | jogAbs = config["ja"]; 352 | syncStart = config["s"]; 353 | // TOOD: pick better name for target in the UI 354 | mc.moveSyncTarget = config["ja"]; 355 | // TODO: need to check if we are rapiding also somewhere! 356 | if(!jogging){ 357 | printf("handleJogAbs target position: %d\n",mc.moveSyncTarget); 358 | 359 | // config["f"] is the feeding_ccw flag from the UI 360 | // TODO: why not set feeding_ccw like we do for handleJog()? 361 | if(config["f"]){ 362 | if((mc.moveSyncTarget - jogAbs) < 0 ){ 363 | z_feeding_dir = true; 364 | stopPos = jogAbs; 365 | //stopNeg = toolRelPosMM; 366 | stopNeg = gs.currentPosition(); 367 | zstepper.setDir(true); 368 | } 369 | else{ 370 | z_feeding_dir = false; 371 | stopNeg = jogAbs; 372 | stopPos = toolRelPosMM; 373 | } 374 | }else{ 375 | if((toolRelPosMM - jogAbs) > 0 ){ 376 | z_feeding_dir = true; 377 | stopPos = jogAbs; 378 | stopNeg = toolRelPosMM; 379 | zstepper.setDir(true); 380 | } 381 | else{ 382 | z_feeding_dir = false; 383 | stopNeg = jogAbs; 384 | stopPos = toolRelPosMM; 385 | } 386 | } 387 | init_pos_feed(); 388 | updateStatusDoc(); 389 | } 390 | */ 391 | } 392 | 393 | // Update the virtual encoder 394 | void handleVencSpeed() 395 | { 396 | 397 | JsonObject config = inDoc["config"]; 398 | vEncSpeed = config["encSpeed"]; 399 | Serial.print(vEncSpeed); 400 | Serial.println("Changing Virtual Encoder! "); 401 | if (vEncSpeed == 0) 402 | { 403 | stopVenc(); 404 | } 405 | if (vEncSpeed > 0 && vEncStopped) 406 | { 407 | startVenc(); 408 | } 409 | } 410 | 411 | void handleRapid() 412 | { 413 | // This just sets the pitch to "rapids" and runs as a normal jog with a faster pitch 414 | 415 | // TODO: calculate speed from current RPM and perhaps warn if accel is a problem? 416 | // really need the acceleration curve 417 | 418 | JsonObject config = inDoc["config"]; 419 | mc.moveDistanceSteps = config["moveSteps"].as(); 420 | mc.rapidPitch = config["rapid"].as(); 421 | // start_rapid(jog_mm); 422 | mc.oldPitch = mc.pitch; 423 | updateStateDoc(); 424 | 425 | Serial.println("Rapid! "); 426 | mc.pitch = mc.rapidPitch; 427 | rapiding = true; 428 | doMoveSync(); 429 | } 430 | 431 | void handleJog() 432 | { 433 | Serial.println("got jog command"); 434 | if (run_mode == RunMode::SLAVE_JOG_READY) 435 | { 436 | JsonObject config = inDoc["config"]; 437 | mc.moveDistanceSteps = config["moveSteps"].as(); 438 | mc.pitch = config["pitch"].as(); 439 | 440 | // TODO: validate this is correct 441 | // TODO: calculate max pitch in init somewhare and compare this 442 | 443 | // don't do this direction is handled in setStops 444 | // mc.moveDirection = (bool)config["f"]; 445 | updateStateDoc(); 446 | doMoveSync(); 447 | } 448 | else 449 | { 450 | el.error("can't jog, no jogging mode is set "); 451 | } 452 | } 453 | void doMoveSync(){ 454 | 455 | if (!pos_feeding) 456 | { 457 | bool thedir = mc.setStops(gs.position); 458 | bool step_dir_response = gs.zstepper.setDirNow(thedir); 459 | Serial.printf("Response from stepper: %d stepper current direction: %d\n",step_dir_response,gs.zstepper.dir); 460 | gs.setELSFactor(mc.pitch); 461 | Serial.printf("doJog pitch: %f target: %i\n",mc.pitch,mc.moveDistanceSteps); 462 | Serial.printf("\t\tStops: stopNeg: %i stopPos: %i\n",mc.stopNeg,mc.stopPos); 463 | //updateStateDoc(); 464 | //updateStatusDoc(); 465 | init_pos_feed(); 466 | } 467 | else 468 | { 469 | el.error("already set feeding, wait till done or cancel"); 470 | } 471 | } 472 | 473 | void handleHobRun() 474 | { 475 | if (run_mode == RunMode::HOB_READY) 476 | { 477 | Serial.println("You should send log msgs to the webapp using the el.xxx thingy."); 478 | Serial.println("got Hob Run"); 479 | // check that we are not already running 480 | if (!pos_feeding) 481 | { 482 | // initialize hob run state? 483 | JsonObject config = inDoc["config"]; 484 | mc.pitch = config["pitch"].as(); 485 | Serial.printf("Pitch %f \n", mc.pitch); 486 | mc.moveDirection = (bool)config["f"]; 487 | // syncStart = (bool)config["s"]; 488 | // TODO: do I need to sync the spindle in this mode? 489 | syncStart = false; 490 | // hob_yasm.next(HobRunState,true); 491 | HobRunState(); 492 | } 493 | else 494 | { 495 | el.error("already feeding, can't set mode to HobRunState"); 496 | } 497 | } 498 | else 499 | { 500 | el.error("previous state wrong, problem!!!"); 501 | } 502 | } 503 | 504 | void handleHobStop() 505 | { 506 | Serial.println("got hob stop"); 507 | HobStopState(); 508 | } 509 | 510 | void handleBounce() 511 | { 512 | Serial.println("Bounce! "); 513 | JsonObject config = inDoc["config"]; 514 | 515 | // parse config 516 | mc.pitch = config["pitch"].as(); 517 | //pitch = mc.pitch; 518 | mc.rapidPitch = config["rapid"].as(); 519 | mc.moveDistanceSteps = config["moveSteps"].as(); 520 | Serial.printf("Bounce config: distance: %i rapid: %lf move: %lf\n",mc.moveDistanceSteps,mc.rapidPitch,mc.pitch); 521 | feeding_ccw = (bool)config["f"]; 522 | //el.error("warning, TOOD: this only is setup for one spindle direction"); 523 | updateStateDoc(); 524 | bouncing = true; 525 | bounce_yasm.next(BounceMoveState,true); 526 | } 527 | 528 | void handleFeed(){ 529 | JsonObject config = inDoc["config"]; 530 | mc.pitch = config["pitch"].as(); 531 | feeding_ccw = (bool)config["f"]; 532 | Serial.printf("\nFeed ccw: %d pitch: %f config pitch %f\n",feeding_ccw,mc.pitch); 533 | //bool d = mc.setStops(gs.currentPosition()); 534 | gs.zstepper.setDirNow(feeding_ccw); 535 | gs.setELSFactor(mc.pitch); 536 | gs.init_gear(encoder.getCount()); 537 | updateStateDoc(); 538 | mc.useStops = false; 539 | syncWaiting = false; 540 | pos_feeding = true; 541 | 542 | } 543 | 544 | void handleDebug() 545 | { 546 | if (inDoc["basic"]) 547 | { 548 | 549 | auto t1 = inDoc["basic"]; 550 | auto t = t1.as(); 551 | if (t == 1) 552 | { 553 | encoder.setCount(encoder.getCount() + 2400); 554 | } 555 | else if (t == 0) 556 | { 557 | encoder.setCount(encoder.getCount() - 2400); 558 | } 559 | else if (t == 2) 560 | { 561 | encoder.dir = true; 562 | encoder.setCount((encoder.getCount() + 1)); 563 | } 564 | else if (t == 3) 565 | { 566 | encoder.dir = false; 567 | encoder.setCount((encoder.getCount() - 1)); 568 | } 569 | } 570 | 571 | if (inDoc["ticks"]) 572 | { 573 | auto ticks = inDoc["ticks"]; 574 | encoder.setCount(encoder.getCount() + ticks.as()); 575 | } 576 | 577 | // Serial.printf("fccw: %d fz: %d sd: %d encDir: %i \n",feeding_ccw,z_feeding_dir,zstepper.dir, encoder.dir); 578 | } 579 | 580 | void handleSend() 581 | { 582 | // this handles config changes sent from UI 583 | 584 | // This seems redundant, why not just access inDoc? 585 | JsonObject config = inDoc["config"]; 586 | Serial.println("getting config"); 587 | if (config["m"] != (int)run_mode) 588 | { 589 | Serial.print("setting new mode from webUI: "); 590 | int got_run_mode = config["m"].as(); 591 | run_mode = RunMode(got_run_mode); 592 | Serial.println((int)run_mode); 593 | setRunMode(got_run_mode); 594 | } 595 | updateStateDoc(); 596 | } 597 | void handleMoveConfig(){ 598 | JsonObject config = inDoc["config"]; 599 | Serial.println("MoveConfig: getting config"); 600 | Serial.print("got pitch: "); 601 | double p = config["movePitch"]; 602 | if(p != mc.pitch){ 603 | Serial.println("new pitch"); 604 | mc.oldPitch = mc.pitch; 605 | mc.pitch = p; 606 | // not needed? 607 | //gs.setELSFactor(mc.pitch); 608 | } 609 | double r = config["rapidPitch"].as(); 610 | if (r != mc.rapidPitch) 611 | { 612 | Serial.println("new rapid"); 613 | mc.rapidPitch = r; 614 | Serial.printf("updating rapids: %lf",mc.rapidPitch); 615 | } 616 | updateStateDoc(); 617 | } 618 | void handleNvConfig() 619 | { 620 | Serial.println("saving configuration"); 621 | JsonObject config = inDoc["config"]; 622 | // TODO better checks than this~ 623 | if (config["lead_screw_pitch"]) 624 | { 625 | // Save 626 | config["i"] = 1; 627 | EepromStream eepromStream(0, 512); 628 | serializeJson(config, eepromStream); 629 | eepromStream.flush(); 630 | loadNvConfigDoc(); 631 | sendNvConfigDoc(); 632 | // reset the den in case a param changed 633 | 634 | gs.setELSFactor(mc.pitch,true); 635 | } 636 | else 637 | { 638 | el.error("error format of NV config bad"); 639 | } 640 | } 641 | 642 | // void parseObj(String msg){ 643 | // This handles deserializing UI msgs and handling commands 644 | // void parseObj(void * param){ 645 | void parseObj(AsyncWebSocketClient *client) 646 | { 647 | DeserializationError error = deserializeJson(inDoc, wsData); 648 | if (error) 649 | { 650 | Serial.print(F("deserializeJson() failed: ")); 651 | Serial.println(error.f_str()); 652 | return; 653 | } 654 | 655 | const char *cmd = inDoc["cmd"]; 656 | if (strcmp(cmd, "helo") == 0) 657 | { 658 | Serial.println("helo received, sending nvconfig"); 659 | const char *uiVsn = inDoc["vsn"]; 660 | if (strcmp(uiVsn, vsn) == 0) 661 | { 662 | sendNvConfigDoc(); 663 | updateStateDoc(); 664 | } 665 | else 666 | { 667 | el.halt("bad version"); 668 | client->close(); 669 | } 670 | } 671 | else if (strcmp(cmd, "fetch") == 0) 672 | { 673 | // regenerate config and send it along 674 | // TODO: compare version here 675 | Serial.println("fetch received: sending config"); 676 | 677 | updateStateDoc(); 678 | } 679 | else if (strcmp(cmd, "debug") == 0) 680 | { 681 | // Debugging tools 682 | handleDebug(); 683 | // JOG COMMANDS 684 | } 685 | else if (strcmp(cmd, "moveCancel") == 0) 686 | { 687 | // TODO wheat cleanup needs to be done? 688 | Serial.println("Move Canceled"); 689 | syncWaiting = false; 690 | pos_feeding = false; 691 | jogging = false; 692 | rapiding = false; 693 | bouncing = false; 694 | 695 | 696 | // this must be reset for moveSync to work after running feed 697 | feeding_ccw = true; 698 | 699 | // TODO: need rapid cancel 700 | } 701 | else if (strcmp(cmd, "moveSyncAbs") == 0) 702 | { 703 | handleJogAbs(); 704 | } 705 | else if (strcmp(cmd, "jog") == 0) 706 | { 707 | handleJog(); 708 | } 709 | else if (strcmp(cmd, "sendConfig") == 0) 710 | { 711 | handleSend(); 712 | } 713 | else if (strcmp(cmd, "sendMoveConfig") == 0){ 714 | handleMoveConfig(); 715 | } 716 | else if (strcmp(cmd, "hobrun") == 0) 717 | { 718 | handleHobRun(); 719 | } 720 | else if (strcmp(cmd, "hobstop") == 0) 721 | { 722 | handleHobStop(); 723 | } 724 | else if (strcmp(cmd, "setNvConfig") == 0) 725 | { 726 | handleNvConfig(); 727 | } 728 | else if (strcmp(cmd, "getNvConfig") == 0) 729 | { 730 | sendNvConfigDoc(); 731 | } 732 | else if (strcmp(cmd, "resetNvConfig") == 0) 733 | { 734 | Serial.println("resetting nv config to defaults"); 735 | initNvConfigDoc(); 736 | sendNvConfigDoc(); 737 | } 738 | else if (strcmp(cmd, "rapid") == 0) 739 | { 740 | handleRapid(); 741 | } 742 | else if (strcmp(cmd, "updateEncSpeed") == 0) 743 | { 744 | handleVencSpeed(); 745 | } 746 | else if (strcmp(cmd, "bounce") == 0) 747 | { 748 | handleBounce(); 749 | } 750 | else if(strcmp(cmd,"feed") == 0) 751 | { 752 | handleFeed(); 753 | } 754 | else if(strcmp(cmd,"ping") == 0){ 755 | Serial.print("^"); 756 | // need to pong to keep alive? 757 | if(client->canSend()){ 758 | ws.binary(client->id(),pongBuf,pong_len); 759 | }else{ 760 | Serial.print("#"); 761 | } 762 | } 763 | else if(strcmp(cmd,"sendDebug") == 0){ 764 | Serial.println("toggle send debug"); 765 | sendDebug = !sendDebug; 766 | } 767 | else 768 | { 769 | Serial.println("unknown command"); 770 | Serial.println(cmd); 771 | } 772 | // vTaskDelete(NULL); 773 | } 774 | 775 | /* 776 | void pinned_parseObj(){ 777 | 778 | xTaskCreatePinnedToCore( 779 | parseObj, // Function that should be called 780 | "ws server", // Name of the task (for debugging) 781 | 32000, // Stack size (bytes) 782 | NULL, // Parameter to pass 783 | 3, // Task priority 784 | NULL, // Task handle 785 | 0 // pin to core 0, arduino loop runs core 1 786 | ); 787 | } 788 | */ 789 | 790 | void onWsEvent(AsyncWebSocket *server, AsyncWebSocketClient *client, AwsEventType type, void *arg, uint8_t *data, size_t len) 791 | { 792 | // Serial.println("ws event"); 793 | if (type == WS_EVT_CONNECT) 794 | { 795 | Serial.printf("Websocket client connection received id: %d\n",client->id()); 796 | globalClient = client; 797 | } 798 | else if (type == WS_EVT_DISCONNECT) 799 | { 800 | Serial.println("Client disconnected"); 801 | Serial.println("-----------------------"); 802 | } 803 | else if (type == WS_EVT_DATA) 804 | { 805 | AwsFrameInfo *info = (AwsFrameInfo *)arg; 806 | if (info->final && info->index == 0 && info->len == len) 807 | { 808 | if (info->opcode == WS_TEXT) 809 | { 810 | data[len] = 0; 811 | // parseObj(String((char*) data)); 812 | wsData = String((char *)data); 813 | parseObj(client); 814 | // pinned_parseObj(); 815 | } 816 | } 817 | } 818 | } 819 | 820 | Ticker reconnectTimer; 821 | 822 | 823 | void connectToWifi() { 824 | Serial.println("reConnecting to Wi-Fi..."); 825 | WiFi.begin(WIFI_SSID, WIFI_PASSWORD); 826 | while (WiFi.status() != WL_CONNECTED) { 827 | Serial.print("."); 828 | delay(100); 829 | } 830 | WiFi.setTxPower(WIFI_POWER_19_5dBm); 831 | WiFi.setAutoReconnect(true); 832 | WiFi.persistent(true); 833 | WiFi.setSleep(false); 834 | Serial.print("Connected. IP="); 835 | Serial.println(WiFi.localIP()); 836 | // MDNS hostname must be lowercase 837 | if (!MDNS.begin(HOSTNAME)) 838 | { 839 | Serial.println("Error setting up MDNS responder!"); 840 | while (1) 841 | { 842 | Serial.print("*"); 843 | delay(100); 844 | } 845 | } 846 | MDNS.setInstanceName(HOSTNAME); 847 | MDNS.addService("http", "tcp", 80); 848 | 849 | ws.onEvent(onWsEvent); 850 | server.addHandler(&ws); 851 | server.begin(); 852 | Serial.println("HTTP websocket server started"); 853 | 854 | } 855 | 856 | void onWifiConnect(WiFiEvent_t event, WiFiEventInfo_t info){ 857 | Serial.println("Connected to Wi-Fi."); 858 | set_error_led_blink(5); 859 | } 860 | 861 | void onWifiDisconnect(WiFiEvent_t event, WiFiEventInfo_t info){ 862 | Serial.println("Disconnected from Wi-Fi. "); 863 | Serial.println(info.wifi_sta_disconnected.reason); 864 | set_error_led_blink(1000); 865 | //reconnectTimer.detach(); // ensure we don't reconnect to MQTT while reconnecting to Wi-Fi 866 | //reconnectTimer.once(5, connectToWifi); 867 | } 868 | 869 | 870 | void init_web() 871 | { 872 | // Connect to WiFi 873 | Serial.println("Setting up WiFi"); 874 | WiFi.setHostname(HOSTNAME); 875 | WiFi.mode(WIFI_MODE_STA); 876 | 877 | //wifiConnectHandler = WiFi.onStationModeGotIP(onWifiConnect); 878 | 879 | WiFi.onEvent(onWifiConnect, WiFiEvent_t::ARDUINO_EVENT_WIFI_STA_GOT_IP); 880 | WiFiEventId_t eventID = WiFi.onEvent(onWifiDisconnect, WiFiEvent_t::ARDUINO_EVENT_WIFI_STA_DISCONNECTED); 881 | 882 | connectToWifi(); 883 | 884 | updateStateDoc(); 885 | init_ota(); 886 | EEPROM.begin(512); 887 | EepromStream eepromStream(0, 512); 888 | deserializeJson(nvConfigDoc, eepromStream); 889 | Serial.println("NV Config? "); 890 | Serial.println((int)nvConfigDoc["i"]); 891 | if (!nvConfigDoc["i"] || KILLNV == 1) 892 | { 893 | Serial.println("creating default nvConfig"); 894 | initNvConfigDoc(); 895 | } 896 | else 897 | { 898 | loadNvConfigDoc(); 899 | } 900 | } 901 | 902 | void init_ota() 903 | { 904 | ArduinoOTA 905 | .onStart([]() 906 | { 907 | String type; 908 | if (ArduinoOTA.getCommand() == U_FLASH) 909 | type = "sketch"; 910 | else // U_SPIFFS 911 | type = "filesystem"; 912 | 913 | // NOTE: if updating SPIFFS this would be the place to unmount SPIFFS using SPIFFS.end() 914 | Serial.println("Start updating " + type); }) 915 | .onEnd([]() 916 | { Serial.println("\nEnd"); }) 917 | .onProgress([](unsigned int progress, unsigned int total) 918 | { Serial.printf("Progress: %u%%\r", (progress / (total / 100))); }) 919 | .onError([](ota_error_t error) 920 | { 921 | Serial.printf("Error[%u]: ", error); 922 | if (error == OTA_AUTH_ERROR) Serial.println("Auth Failed"); 923 | else if (error == OTA_BEGIN_ERROR) Serial.println("Begin Failed"); 924 | else if (error == OTA_CONNECT_ERROR) Serial.println("Connect Failed"); 925 | else if (error == OTA_RECEIVE_ERROR) Serial.println("Receive Failed"); 926 | else if (error == OTA_END_ERROR) Serial.println("End Failed"); }); 927 | 928 | ArduinoOTA.begin(); 929 | } 930 | void sendUpdates() 931 | { 932 | // called in main loop 933 | if (update_timer.repeat()) 934 | { 935 | // only send state when it changes 936 | // updateStateDoc(); 937 | // Serial.printf(" %d ",(int)run_mode); 938 | Serial.printf(" %d %d %d ", (int)run_mode, gs.position, WiFi.RSSI()); 939 | updateDebugStatusDoc(); 940 | updateStatusDoc(); 941 | 942 | ws.cleanupClients(); 943 | } 944 | } 945 | void do_web() 946 | { 947 | if (web) 948 | { 949 | if(ota_timer.repeat()){ 950 | ArduinoOTA.handle(); 951 | } 952 | } 953 | } 954 | -------------------------------------------------------------------------------- /src/src/web.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include "config.h" 4 | #include "WiFi.h" 5 | #include "ESPAsyncWebServer.h" 6 | //#include "c:\Users\jesse\Documents\Arduino\config.h" 7 | #include 8 | #include 9 | #include 10 | // #include 11 | 12 | extern bool web; 13 | 14 | void init_web(void); 15 | void do_web(void); 16 | void init_ota(void); 17 | void updateStateDoc(); 18 | void updateStatusDoc(); 19 | void sendState(); 20 | void sendStatus(); 21 | void sendLogP(Log::Msg *msg); 22 | void loadNvConfigDoc(); 23 | void handleJog(); 24 | void sendUpdates(); 25 | void sendDoc(const JsonDocument& doc); 26 | void sendLogP(Log::Msg *msg); 27 | void setRunMode(int mode); 28 | void doMoveSync(); 29 | -------------------------------------------------------------------------------- /test/README: -------------------------------------------------------------------------------- 1 | 2 | This directory is intended for PlatformIO Unit Testing and project tests. 3 | 4 | Unit Testing is a software testing method by which individual units of 5 | source code, sets of one or more MCU program modules together with associated 6 | control data, usage procedures, and operating procedures, are tested to 7 | determine whether they are fit for use. Unit testing finds problems early 8 | in the development cycle. 9 | 10 | More information about PlatformIO Unit Testing: 11 | - https://docs.platformio.org/page/plus/unit-testing.html 12 | -------------------------------------------------------------------------------- /test/test_desktop/test_gear.cpp: -------------------------------------------------------------------------------- 1 | #ifdef UNIT_TEST 2 | 3 | #include 4 | #include "src/Gear.h" 5 | #include 6 | 7 | 8 | // yuck 9 | 10 | int Gear::State::next; 11 | int Gear::State::prev; 12 | int Gear::State::last; 13 | 14 | void printJump(char *s,Gear::Jump j){ 15 | std::cout << s << "jump delta " << j.delta << " , "; 16 | std::cout << "count " << j.count << " , "; 17 | std::cout << "error" << j.error<< "\n"; 18 | 19 | 20 | } 21 | 22 | void setUp(void) { 23 | // set stuff up here 24 | } 25 | 26 | void tearDown(void) { 27 | // clean stuff up here 28 | } 29 | 30 | 31 | 32 | int main( int argc, char **argv) { 33 | UNITY_BEGIN(); 34 | 35 | 36 | /* 37 | 38 | what is a jump? 39 | struct of count, delta, and error 40 | 41 | k = encoder_pulses per step 42 | 43 | count returned by jump is count+k where k is calculated by next_jump_forward or next_jump_reverse 44 | 45 | */ 46 | 47 | 48 | /* 49 | 50 | What is a Range? 51 | 52 | it seems range just runs next_jump_forward and next_jump_reverse and returns the two 53 | results as {Jump next, Jump prev}, the ranges are only calculated once the encoder count reaches the count in the 54 | next/prev jumps 55 | 56 | */ 57 | 58 | Gear::State state; 59 | state.output_position = 0; 60 | int micro_steps = 8; 61 | int motor_steps = 200 * micro_steps; 62 | //float pitch = 4; 63 | float pitch = 0.1; 64 | float lead_screw_pitch = 2.0; 65 | int enc_res = 2400; 66 | 67 | int den = lead_screw_pitch * enc_res; 68 | int nom = motor_steps * pitch; 69 | 70 | std::cout << "nom: " << nom << " / den: " << den << "\n"; 71 | std::cout << "test empty " << state.output_position << "\n"; 72 | 73 | 74 | 75 | int start = -10; 76 | int stop = 169; 77 | state.output_position = start; 78 | bool test = state.setRatio(nom,den); 79 | 80 | TEST_ASSERT_EQUAL_INT(1,(int)test); 81 | 82 | int e = 0; 83 | 84 | 85 | // this changes the formula 86 | bool dir = true; 87 | state.calc_jumps(start,dir); 88 | 89 | std::cout << "starting jumps: " << state.prev << " - " << state.next << "\n"; 90 | TEST_ASSERT_EQUAL_INT(-26,state.prev); 91 | 92 | TEST_ASSERT_EQUAL_INT(5,state.next); 93 | 94 | 95 | for(int i = start;i < stop + 1;i++){ 96 | // if the "encoder" is incrementing 97 | 98 | // calculate both forward and reverse 99 | 100 | if(i == state.next ) { 101 | state.calc_jumps(i,dir); 102 | //std::cout << "+ p:" << Gear::state.jumps.prev << " -- count: "<< i << " -- n: " 103 | //<< Gear::state.jumps.next << "+"; 104 | std::cout << "*" << i << "," << state.next << "," << state.prev << " "; 105 | } 106 | 107 | 108 | } 109 | 110 | //state.calc_jumps(stop,dir); 111 | state.prev = state.last; 112 | std::cout << "\nREVERSE\n\n"; 113 | std::cout << "next: " << state.next << " prev: " << state.prev << " err: " << state.perror << "\n"; 114 | 115 | TEST_ASSERT_EQUAL_INT(185, state.next); 116 | TEST_ASSERT_EQUAL_INT(155, state.prev); 117 | TEST_ASSERT_EQUAL_INT(2240,state.perror); 118 | 119 | // does this do anything? 120 | for(int i = stop +2;i > (start + 1);i--){ 121 | if(i == state.prev){ 122 | state.calc_jumps(i,dir); 123 | //std::cout << "@" << i << " "; 124 | std::cout << "@" << i << "," << state.next << "," << state.prev << " "; 125 | //std::cout << "next: " << state.jumps.next << " prev: " << state.jumps.prev << "\n"; 126 | } 127 | } 128 | 129 | return 0; 130 | UNITY_END(); 131 | } 132 | 133 | #endif 134 | -------------------------------------------------------------------------------- /test/test_pos/test_pos.cpp: -------------------------------------------------------------------------------- 1 | #ifdef UNIT_TEST 2 | 3 | #include 4 | #include 5 | 6 | 7 | void playPos(){ 8 | 9 | std::cout << "bsz\n"; 10 | } 11 | 12 | void setUp(void) { 13 | // set stuff up here 14 | } 15 | 16 | void tearDown(void) { 17 | // clean stuff up here 18 | //TEST_ASSERT_TRUE(false); 19 | } 20 | 21 | int main( int argc, char **argv) { 22 | UNITY_BEGIN(); 23 | 24 | //Pos startPos; 25 | 26 | std::cout << "foo\n"; 27 | //Serial.println("foobar"); 28 | RUN_TEST(playPos); 29 | 30 | return 0; 31 | UNITY_END(); 32 | } 33 | 34 | #endif 35 | -------------------------------------------------------------------------------- /test/test_speed/test_speed.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | 4 | //#include //redirects to ArduinoFake.h in this case 5 | #include 6 | #include 7 | #include "src/log.h" 8 | 9 | #define Z_NATIVE_STEPS_PER_REV 200 10 | #define Z_MICROSTEPPING 8 11 | 12 | 13 | #include "src/genStepper.h" 14 | #include "src/moveConfig.h" 15 | #include "src/mocks.h" 16 | 17 | 18 | // brittle 19 | 20 | Gear::State GenStepper::State::mygear; 21 | rmtStepper::State GenStepper::State::zstepper; 22 | int GenStepper::State::nom; 23 | int GenStepper::State::den; 24 | int GenStepper::State::position; 25 | int32_t MoveConfig::State::moveTargetSteps ; 26 | int32_t MoveConfig::State::moveDistanceSteps ; 27 | bool MoveConfig::State::waitForSync ; 28 | bool MoveConfig::State::moveDirection ; 29 | //int32_t MoveConfig::State::moveSyncTarget ; 30 | int MoveConfig::State::stopPos ; 31 | int MoveConfig::State::stopNeg ; 32 | bool MoveConfig::State::spindle_handedness ; 33 | double MoveConfig::State::pitch ; 34 | double MoveConfig::State::rapidPitch ; 35 | double MoveConfig::State::oldPitch ; 36 | //bool MoveConfig::State::syncMoveStart ; 37 | //bool MoveConfig::State::isAbs ; 38 | bool MoveConfig::State::useStops ; 39 | int Gear::State::next; 40 | int Gear::State::prev; 41 | int Gear::State::last; 42 | 43 | 44 | using namespace fakeit; 45 | 46 | // run using `pio test -e ESPelsTest -v` 47 | // debug `pio debug -e ESPelsTest --interface gdb -x .pioinit` 48 | 49 | #define UNITY_INCLUDE_EXEC_TIME 50 | 51 | 52 | void tearDown(void) { 53 | // clean stuff up here 54 | //TEST_ASSERT_TRUE(false); 55 | } 56 | 57 | void setUp(void) 58 | { 59 | ArduinoFakeReset(); 60 | } 61 | 62 | void setup(){ 63 | 64 | } 65 | void loop(){ 66 | 67 | } 68 | 69 | 70 | void test_venc_moveSync(){ 71 | Log::Msg lm; 72 | 73 | GenStepper::Config gconf = { 74 | 0, 75 | "Z", 76 | 2.0, // lead screw pitch 77 | 2400, // spindle enc resolution 78 | 200, // native steps 79 | 8 // microsteps 80 | }; 81 | 82 | GenStepper::State gs = GenStepper::init("Z",lm,gconf); 83 | MoveConfig::State mc = MoveConfig::init(); 84 | gs.c.spindle_encoder_resolution = 1000; 85 | gs.c.lead_screw_pitch = 1.0; 86 | gs.c.motor_steps = 1000; 87 | 88 | 89 | bool t = gs.setELSFactor(1,true); 90 | TEST_ASSERT(t == true); 91 | std::cout << "nom: " << gs.nom << " den: " << gs.den << "\n"; 92 | 93 | int64_t pulse_counter = 0; 94 | t = gs.init_gear(pulse_counter); 95 | gs.mygear.calc_jumps(pulse_counter,true); 96 | int ts = 1000000; 97 | auto start = std::chrono::steady_clock::now(); 98 | for(int i = 0;i <= ts;i++){ 99 | if(i == gs.mygear.next || i == gs.mygear.prev){ 100 | gs.mygear.calc_jumps(i); 101 | gs.step(); 102 | } 103 | } 104 | auto stop = std::chrono::steady_clock::now(); 105 | auto duration = std::chrono::duration_cast(stop - start); 106 | //auto duration = (start - stop); 107 | int counter = duration.count(); 108 | std::cout << "time for bench: " << counter << " us\n"; 109 | TEST_ASSERT_EQUAL_INT(ts,gs.position ); 110 | 111 | 112 | 113 | } 114 | 115 | int main( int argc, char **argv) { 116 | UNITY_BEGIN(); 117 | RUN_TEST(test_venc_moveSync); 118 | return UNITY_END(); 119 | } 120 | 121 | -------------------------------------------------------------------------------- /test/test_stepper/test_stepper.cpp: -------------------------------------------------------------------------------- 1 | #include //redirects to ArduinoFake.h in this case 2 | #include 3 | #include 4 | #include "src/log.h" 5 | 6 | 7 | #define Z_NATIVE_STEPS_PER_REV 200 8 | #define Z_MICROSTEPPING 8 9 | 10 | #include "src/genStepper.h" 11 | #include "src/moveConfig.h" 12 | #include "src/mocks.h" 13 | 14 | using namespace fakeit; 15 | 16 | 17 | // static init 18 | Gear::State GenStepper::State::mygear; 19 | rmtStepper::State GenStepper::State::zstepper; 20 | int GenStepper::State::nom; 21 | int GenStepper::State::den; 22 | int GenStepper::State::position; 23 | int32_t MoveConfig::State::moveTargetSteps ; 24 | int32_t MoveConfig::State::moveDistanceSteps ; 25 | bool MoveConfig::State::waitForSync ; 26 | bool MoveConfig::State::moveDirection ; 27 | //int32_t MoveConfig::State::moveSyncTarget ; 28 | int MoveConfig::State::stopPos ; 29 | int MoveConfig::State::stopNeg ; 30 | bool MoveConfig::State::spindle_handedness ; 31 | double MoveConfig::State::pitch ; 32 | double MoveConfig::State::rapidPitch ; 33 | double MoveConfig::State::oldPitch ; 34 | //bool MoveConfig::State::syncMoveStart ; 35 | //bool MoveConfig::State::isAbs ; 36 | bool MoveConfig::State::useStops ; 37 | int Gear::State::next; 38 | int Gear::State::prev; 39 | int Gear::State::last; 40 | 41 | Log::Msg lm; 42 | GenStepper::Config gconf = { 43 | 0, 44 | "Z", 45 | 2.0, // lead screw pitch 46 | 2400, // spindle enc resolution 47 | 200, // native steps 48 | 8 // microsteps 49 | }; 50 | GenStepper::State gs = GenStepper::init("z",lm,gconf); 51 | MoveConfig::State mc = MoveConfig::init(); 52 | 53 | // run using `pio test -e ESPelsTest -v` 54 | // debug `pio debug -e ESPelsTest --interface gdb -x .pioinit` 55 | 56 | void tearDown(void) 57 | { 58 | // clean stuff up here 59 | // TEST_ASSERT_TRUE(false); 60 | } 61 | 62 | void setUp(void) 63 | { 64 | ArduinoFakeReset(); 65 | } 66 | 67 | void setup() 68 | { 69 | } 70 | void loop() 71 | { 72 | } 73 | 74 | void test_genstepper() 75 | { 76 | std::cout << "test_genstepper\n"; 77 | Log::Msg lm; 78 | // GenStepper::State gs; 79 | GenStepper::Config gconf = { 80 | 0, 81 | "Z", 82 | 2.0, // lead screw pitch 83 | 2400, // spindle enc resolution 84 | 200, // native steps 85 | 8, // microsteps 86 | 1600 87 | }; 88 | GenStepper::State gs = GenStepper::init("Z", lm,gconf); 89 | 90 | TEST_ASSERT(gs.c.dir == 0); 91 | 92 | std::cout << "name: " << gs.c.name << " pitch: " << mc.pitch << "\n"; 93 | 94 | 95 | gs.mygear.calc_jumps(100, true); 96 | std::cout << "gear nom: " << gs.mygear.N << " den: " << gs.mygear.D << " \n"; 97 | std::cout << "gs nom: " << gs.nom << " den: " << gs.den << " \n"; 98 | TEST_ASSERT(gs.nom != 0); 99 | TEST_ASSERT(gs.den != 0); 100 | // should be 1:1 max and jumps should happen every encoder tick 101 | std::cout << "jumps: " << gs.mygear.jumps.last << " - " << gs.mygear.jumps.prev << "\n"; 102 | gs.setELSFactor(2.0); 103 | std::cout << "gear nom: " << gs.mygear.N << " den: " << gs.mygear.D << " \n"; 104 | gs.mygear.calc_jumps(100, true); 105 | std::cout << "jumps: " << gs.mygear.jumps.last << " - " << gs.mygear.jumps.prev << "\n"; 106 | 107 | bool fails_zero_pitch = gs.setELSFactor(0, false); 108 | TEST_ASSERT(fails_zero_pitch == false); 109 | } 110 | void test_moveConfig() 111 | { 112 | std::cout << "test_moveConfig\n"; 113 | Log::Msg lm; 114 | MoveConfig::State mc = MoveConfig::init(); 115 | 116 | // test abs move from "0" to 1000 steps 117 | int distance = 1000; 118 | mc.moveDistanceSteps = distance; 119 | 120 | // TODO: do we always set the stepper when we set the stops? If so consider factoring this out 121 | bool r = mc.setStops(0); 122 | gs.zstepper.setDir(r); 123 | 124 | std::cout 125 | << "step dir bool: " << r << " stopPos: " << mc.stopPos << " stopNeg: " << mc.stopNeg << " target: " << mc.moveDistanceSteps << "\n"; 126 | TEST_ASSERT(r); 127 | TEST_ASSERT(mc.stopPos == distance); 128 | } 129 | 130 | void test_fakePosFeeding() 131 | { 132 | std::cout << "test_fakePosFeeding\n"; 133 | Log::Msg lm; 134 | // How it works 135 | // 1.record current encoder position 136 | // 2. sanity check to make sure jumps are sane 137 | // 3. deal with spindle direction changes 138 | // 4. deal with dir change pauses for stepper 139 | // 5. evaluate if we have reached a "jump" 140 | // 6. if yes command stepper 141 | // 7. evaluate stops, if reached finish move 142 | 143 | // Impl 144 | 145 | GenStepper::Config gconf = { 146 | 0, 147 | "Z", 148 | 2.0, // lead screw pitch 149 | 2400, // spindle enc resolution 150 | 200, // native steps 151 | 8, // microsteps 152 | 1600 // motor_steps this should be calculated from native steps and microsteps 153 | }; 154 | GenStepper::State gs = GenStepper::init("Z", lm,gconf); 155 | MoveConfig::State mc = MoveConfig::init(); 156 | 157 | // record current encoder position 158 | // int64_t pulse_counter = encoder.getCount(); 159 | 160 | // setup 161 | // bool t = true; 162 | int64_t pulse_counter = 100; 163 | bool t = gs.setELSFactor(0.1); 164 | 165 | TEST_ASSERT(t == true); 166 | 167 | 168 | gs.mygear.calc_jumps(pulse_counter, true); 169 | 170 | // sanity check to make sure jumps are sane 171 | 172 | if (pulse_counter > gs.mygear.next + 1 || pulse_counter < gs.mygear.prev - 1) 173 | { 174 | std::cout << "doh! sanity check fail\n"; 175 | std::cout << gs.mygear.next + 1 << " prev: " << gs.mygear.prev - 1 << "\n"; 176 | } 177 | else 178 | { 179 | std::cout << "sanity check passed\n"; 180 | } 181 | 182 | // deal with spindle direction changes 183 | 184 | // skipping, need to test in encoder tests 185 | 186 | // deal with dir change pauses for stepper 187 | 188 | // this goes away with fastaccelstepper 189 | 190 | // evaluate if we have reached a "jump" 191 | 192 | // based on pitch 0.1 and default setup we should be at a jump 193 | // TEST_ASSERT_EQUAL_INT(99,gs.mygear.jumps.next ); 194 | 195 | // if yes command stepper 196 | 197 | gs.stepPos(); 198 | TEST_ASSERT(1 == gs.position); 199 | gs.zstepper.setDir(false); 200 | gs.stepNeg(); 201 | TEST_ASSERT(0 == gs.position); 202 | 203 | // evaluate stops, if reached finish move 204 | 205 | std::cout << "done\n"; 206 | } 207 | void test_venc_moveSync() 208 | { 209 | std::cout << "test_venc_moveSync \n"; 210 | Log::Msg lm; 211 | 212 | 213 | GenStepper::Config gconf = { 214 | 0, 215 | "Z", 216 | 2.0, // lead screw pitch 217 | 2400, // spindle enc resolution 218 | 200, // native steps 219 | 8, // microsteps 220 | 1600 // motorsteps 221 | }; 222 | GenStepper::State gs = GenStepper::init("Z", lm,gconf); 223 | MoveConfig::State mc = MoveConfig::init(); 224 | gs.c.spindle_encoder_resolution = 1000; 225 | gs.c.lead_screw_pitch = 1.0; 226 | gs.c.motor_steps = 1000; 227 | 228 | bool t = gs.setELSFactor(1, true); 229 | TEST_ASSERT(t == true); 230 | std::cout << "nom: " << gs.nom << " den: " << gs.den << "\n"; 231 | 232 | int64_t pulse_counter = 0; 233 | t = gs.init_gear(pulse_counter); 234 | gs.mygear.calc_jumps(pulse_counter, true); 235 | for (int i = 0; i <= 10; i++) 236 | { 237 | if (i == gs.mygear.next || i == gs.mygear.prev) 238 | { 239 | gs.mygear.calc_jumps(i); 240 | gs.step(); 241 | } 242 | } 243 | TEST_ASSERT_EQUAL_INT(10, gs.position); 244 | } 245 | 246 | void test_venc_moveAbsSync() 247 | { 248 | TEST_ASSERT(false); 249 | } 250 | 251 | void test_bad_config(){ 252 | 253 | std::cout << "test_bad_config\n"; 254 | Log::Msg lm; 255 | 256 | GenStepper::Config gconf = { 257 | 0, 258 | "Z", 259 | 2.0, // lead screw pitch 260 | 2400, // spindle enc resolution 261 | 200, // native steps 262 | 8 // microsteps 263 | // **** missing motor_steps 264 | }; 265 | GenStepper::State gs = GenStepper::init("Z", lm,gconf); 266 | MoveConfig::State mc = MoveConfig::init(); 267 | 268 | 269 | gs.init_gear(0); 270 | bool bad = gs.setELSFactor(0.1,true); 271 | TEST_ASSERT_EQUAL(false,bad); 272 | } 273 | 274 | int main(int argc, char **argv) 275 | { 276 | UNITY_BEGIN(); 277 | //When(Method(ArduinoFake(), Serial)).AlwaysReturn(); 278 | std::cout << "stepper test\n"; 279 | RUN_TEST(test_genstepper); 280 | RUN_TEST(test_moveConfig); 281 | RUN_TEST(test_venc_moveSync); 282 | // TODO: get abs working 283 | // RUN_TEST(test_venc_moveAbsSync); 284 | RUN_TEST(test_fakePosFeeding); 285 | RUN_TEST(test_bad_config); 286 | return UNITY_END(); 287 | } 288 | --------------------------------------------------------------------------------