Repository: pkerspe/ESP-StepperMotor-Server Branch: master Commit: 4d5ee75a5292 Files: 42 Total size: 376.8 KB Directory structure: gitextract_n8jre_j7/ ├── .github/ │ ├── FUNDING.yml │ ├── ISSUE_TEMPLATE/ │ │ ├── bug_report.md │ │ └── feature_request.md │ ├── scripts/ │ │ ├── install-arduino-core-esp32.sh │ │ ├── install-arduino-ide.sh │ │ ├── install-platformio.sh │ │ └── on-push.sh │ └── workflows/ │ └── push.yml ├── .gitignore ├── Documentation.md ├── LICENSE.txt ├── README.md ├── examples/ │ ├── Example1_BasicESPStepperMotorServer/ │ │ └── Example1_BasicESPStepperMotorServer.ino │ ├── Example2_StepperMotorServer_with_hardcoded_config/ │ │ └── Example2_StepperMotorServer_with_hardcoded_config.ino │ ├── Example3_StepperMotorServer_with_static_IP_address/ │ │ └── Example3_StepperMotorServer_with_static_IP_address.ino │ └── Example4_StepperMotorServer_with_user_cli_command/ │ └── Example4_StepperMotorServer_with_user_cli_command.ino ├── library.json ├── library.properties ├── platformio.ini └── src/ ├── ESPStepperMotorServer.cpp ├── ESPStepperMotorServer.h ├── ESPStepperMotorServer_CLI.cpp ├── ESPStepperMotorServer_CLI.h ├── ESPStepperMotorServer_Configuration.cpp ├── ESPStepperMotorServer_Configuration.h ├── ESPStepperMotorServer_Logger.cpp ├── ESPStepperMotorServer_Logger.h ├── ESPStepperMotorServer_MacroAction.cpp ├── ESPStepperMotorServer_MacroAction.h ├── ESPStepperMotorServer_MotionController.cpp ├── ESPStepperMotorServer_MotionController.h ├── ESPStepperMotorServer_PositionSwitch.cpp ├── ESPStepperMotorServer_PositionSwitch.h ├── ESPStepperMotorServer_RestAPI.cpp ├── ESPStepperMotorServer_RestAPI.h ├── ESPStepperMotorServer_RotaryEncoder.cpp ├── ESPStepperMotorServer_RotaryEncoder.h ├── ESPStepperMotorServer_StepperConfiguration.cpp ├── ESPStepperMotorServer_StepperConfiguration.h ├── ESPStepperMotorServer_WebInterface.cpp ├── ESPStepperMotorServer_WebInterface.h └── main.cpp ================================================ FILE CONTENTS ================================================ ================================================ FILE: .github/FUNDING.yml ================================================ # These are supported funding model platforms github: [pkerspe] ================================================ FILE: .github/ISSUE_TEMPLATE/bug_report.md ================================================ --- name: Bug report about: Create a report to help us improve title: '' labels: '' assignees: '' --- **Describe the bug** A clear and concise description of what the bug is. **Environment** Please describe which IDE you are using (Arduino or PlatformIO) and which Version of the Library you are using. Also Please provide the Library versions of the depency libraries (ESP-FlexyStepper, AsyncWebserver, ArduinoJSON) **To Reproduce** PLease describe the steps to reproduce the behavior: 1. Go to '...' 2. Click on '....' 3. Scroll down to '....' 4. See error **Expected behavior** A clear and concise description of what you expected to happen. **Screenshots** If applicable, add screenshots to help explain your problem. **Additional context** Add any other context about the problem here. ================================================ FILE: .github/ISSUE_TEMPLATE/feature_request.md ================================================ --- name: Feature request about: Suggest an idea for this project title: '' labels: '' assignees: '' --- **Is your feature request related to a problem? Please describe.** A clear and concise description of what the problem is. Ex. I'm always frustrated when [...] **Describe the solution you'd like** A clear and concise description of what you want to happen. **Describe alternatives you've considered** A clear and concise description of any alternative solutions or features you've considered. **Additional context** Add any other context or screenshots about the feature request here. ================================================ FILE: .github/scripts/install-arduino-core-esp32.sh ================================================ #!/bin/bash export ARDUINO_ESP32_PATH="$ARDUINO_USR_PATH/hardware/espressif/esp32" if [ ! -d "$ARDUINO_ESP32_PATH" ]; then echo "Installing ESP32 Arduino Core ..." script_init_path="$PWD" mkdir -p "$ARDUINO_USR_PATH/hardware/espressif" cd "$ARDUINO_USR_PATH/hardware/espressif" echo "Installing Python Serial ..." pip install pyserial > /dev/null if [ "$OS_IS_WINDOWS" == "1" ]; then echo "Installing Python Requests ..." pip install requests > /dev/null fi if [ "$GITHUB_REPOSITORY" == "espressif/arduino-esp32" ]; then echo "Linking Core..." ln -s $GITHUB_WORKSPACE esp32 else echo "Cloning Core Repository..." git clone https://github.com/espressif/arduino-esp32.git esp32 > /dev/null 2>&1 fi echo "Updating Submodules ..." cd esp32 git submodule update --init --recursive > /dev/null 2>&1 echo "Installing Platform Tools ..." cd tools && python get.py cd $script_init_path echo "ESP32 Arduino has been installed in '$ARDUINO_ESP32_PATH'" echo "" fi ================================================ FILE: .github/scripts/install-arduino-ide.sh ================================================ #!/bin/bash #OSTYPE: 'linux-gnu', ARCH: 'x86_64' => linux64 #OSTYPE: 'msys', ARCH: 'x86_64' => win32 #OSTYPE: 'darwin18', ARCH: 'i386' => macos OSBITS=$(arch) if [[ "$OSTYPE" == "linux"* ]]; then export OS_IS_LINUX="1" ARCHIVE_FORMAT="tar.xz" if [[ "$OSBITS" == "i686" ]]; then OS_NAME="linux32" elif [[ "$OSBITS" == "x86_64" ]]; then OS_NAME="linux64" elif [[ "$OSBITS" == "armv7l" || "$OSBITS" == "aarch64" ]]; then OS_NAME="linuxarm" else OS_NAME="$OSTYPE-$OSBITS" echo "Unknown OS '$OS_NAME'" exit 1 fi elif [[ "$OSTYPE" == "darwin"* ]]; then export OS_IS_MACOS="1" ARCHIVE_FORMAT="zip" OS_NAME="macosx" elif [[ "$OSTYPE" == "cygwin" ]] || [[ "$OSTYPE" == "msys" ]] || [[ "$OSTYPE" == "win32" ]]; then export OS_IS_WINDOWS="1" ARCHIVE_FORMAT="zip" OS_NAME="windows" else OS_NAME="$OSTYPE-$OSBITS" echo "Unknown OS '$OS_NAME'" exit 1 fi export OS_NAME ARDUINO_BUILD_DIR="$HOME/.arduino/build.tmp" ARDUINO_CACHE_DIR="$HOME/.arduino/cache.tmp" if [ "$OS_IS_MACOS" == "1" ]; then export ARDUINO_IDE_PATH="/Applications/Arduino.app/Contents/Java" export ARDUINO_USR_PATH="$HOME/Documents/Arduino" elif [ "$OS_IS_WINDOWS" == "1" ]; then export ARDUINO_IDE_PATH="$HOME/arduino_ide" export ARDUINO_USR_PATH="$HOME/Documents/Arduino" else export ARDUINO_IDE_PATH="$HOME/arduino_ide" export ARDUINO_USR_PATH="$HOME/Arduino" fi if [ ! -d "$ARDUINO_IDE_PATH" ]; then echo "Installing Arduino IDE on $OS_NAME ..." echo "Downloading 'arduino-nightly-$OS_NAME.$ARCHIVE_FORMAT' to 'arduino.$ARCHIVE_FORMAT' ..." if [ "$OS_IS_LINUX" == "1" ]; then wget -O "arduino.$ARCHIVE_FORMAT" "https://www.arduino.cc/download.php?f=/arduino-nightly-$OS_NAME.$ARCHIVE_FORMAT" > /dev/null 2>&1 echo "Extracting 'arduino.$ARCHIVE_FORMAT' ..." tar xf "arduino.$ARCHIVE_FORMAT" > /dev/null mv arduino-nightly "$ARDUINO_IDE_PATH" else curl -o "arduino.$ARCHIVE_FORMAT" -L "https://www.arduino.cc/download.php?f=/arduino-nightly-$OS_NAME.$ARCHIVE_FORMAT" > /dev/null 2>&1 echo "Extracting 'arduino.$ARCHIVE_FORMAT' ..." unzip "arduino.$ARCHIVE_FORMAT" > /dev/null if [ "$OS_IS_MACOS" == "1" ]; then mv "Arduino.app" "/Applications/Arduino.app" else mv arduino-nightly "$ARDUINO_IDE_PATH" fi fi rm -rf "arduino.$ARCHIVE_FORMAT" mkdir -p "$ARDUINO_USR_PATH/libraries" mkdir -p "$ARDUINO_USR_PATH/hardware" echo "Arduino IDE Installed in '$ARDUINO_IDE_PATH'" echo "" fi function build_sketch(){ # build_sketch [extra-options] if [ "$#" -lt 2 ]; then echo "ERROR: Illegal number of parameters" echo "USAGE: build_sketch [extra-options]" return 1 fi local fqbn="$1" local sketch="$2" local build_flags="$3" local xtra_opts="$4" local win_opts="" if [ "$OS_IS_WINDOWS" == "1" ]; then local ctags_version="ls \"$ARDUINO_IDE_PATH/tools-builder/ctags/\"" local preprocessor_version="ls \"$ARDUINO_IDE_PATH/tools-builder/arduino-preprocessor/\"" win_opts="-prefs=runtime.tools.ctags.path=$ARDUINO_IDE_PATH/tools-builder/ctags/$ctags_version -prefs=runtime.tools.arduino-preprocessor.path=$ARDUINO_IDE_PATH/tools-builder/arduino-preprocessor/$preprocessor_version" fi echo "" echo "Compiling '\"$(basename "$sketch")\"' ..." mkdir -p "$ARDUINO_BUILD_DIR" mkdir -p "$ARDUINO_CACHE_DIR" "$ARDUINO_IDE_PATH/arduino-builder -compile -logger=human -core-api-version=10810 \ -fqbn=$fqbn \ -warnings=\"all\" \ -tools \"$ARDUINO_IDE_PATH/tools-builder\" \ -tools \"$ARDUINO_IDE_PATH/tools\" \ -built-in-libraries \"$ARDUINO_IDE_PATH/libraries\" \ -hardware \"$ARDUINO_IDE_PATH/hardware\" \ -hardware \"$ARDUINO_USR_PATH/hardware\" \ -libraries \"$ARDUINO_USR_PATH/libraries\" \ -build-cache \"$ARDUINO_CACHE_DIR\" \ -build-path \"$ARDUINO_BUILD_DIR\" \ -prefs=compiler.cpp.extra_flags=\"$build_flags\" \ $win_opts $xtra_opts \"$sketch\"" } function count_sketches() # count_sketches { local examples="$1" rm -rf sketches.txt if [ ! -d "$examples" ]; then touch sketches.txt return 0 fi local sketches=$(find $examples -name *.ino) local sketchnum=0 for sketch in $sketches; do echo "found $sketch" local sketchdir=$(dirname $sketch) local sketchdirname=$(basename $sketchdir) local sketchname=$(basename $sketch) if [[ "${sketchdirname}.ino" != "$sketchname" ]]; then continue fi; if [[ -f "$sketchdir/.test.skip" ]]; then continue fi echo $sketch >> sketches.txt sketchnum=($sketchnum + 1) done return $sketchnum } function build_sketches() # build_sketches [extra-options] { local fqbn=$1 local examples=$2 local chunk_idex=$3 local chunks_num=$4 local xtra_opts=$5 if [ "$#" -lt 2 ]; then echo "ERROR: Illegal number of parameters" echo "USAGE: build_sketches [ ] [extra-options]" return 1 fi if [ "$#" -lt 4 ]; then chunk_idex="0" chunks_num="1" xtra_opts=$3 fi if [ "$chunks_num" -le 0 ]; then echo "ERROR: Chunks count must be positive number" return 1 fi if [ "$chunk_idex" -ge "$chunks_num" ]; then echo "ERROR: Chunk index must be less than chunks count" return 1 fi set +e count_sketches "$examples" local sketchcount=$? set -e local sketches=$(cat sketches.txt) rm -rf sketches.txt local chunk_size=( $sketchcount / $chunks_num ) local all_chunks=( $chunks_num * $chunk_size ) if [ "$all_chunks" -lt "$sketchcount" ]; then chunk_size=( $chunk_size + 1 ) fi local start_index=( $chunk_idex * $chunk_size ) if [ "$sketchcount" -le "$start_index" ]; then echo "Skipping job" return 0 fi local end_index=( $chunk_idex + 1 ) * $chunk_size if [ "$end_index" -gt "$sketchcount" ]; then end_index=$sketchcount fi local start_num=( $start_index + 1 ) echo "Found $sketchcount Sketches"; echo "Chunk Count : $chunks_num" echo "Chunk Size : $chunk_size" echo "Start Sketch: $start_num" echo "End Sketch : $end_index" local sketchnum=0 for sketch in $sketches; do local sketchdir=$(dirname $sketch) local sketchdirname=$(basename $sketchdir) local sketchname=$(basename $sketch) if [ "${sketchdirname}.ino" != "$sketchname" ] \ || [ -f "$sketchdir/.test.skip" ]; then continue fi sketchnum=$(($sketchnum + 1)) if [ "$sketchnum" -le "$start_index" ] \ || [ "$sketchnum" -gt "$end_index" ]; then continue fi local sketchBuildFlags="" if [ -f "$sketchdir/.test.build_flags" ]; then while read line; do sketchBuildFlags="$sketchBuildFlags $line" done < "$sketchdir/.test.build_flags" fi build_sketch "$fqbn" "$sketch" "$sketchBuildFlags" "$xtra_opts" local result=$? if [ $result -ne 0 ]; then return $result fi done return 0 } ================================================ FILE: .github/scripts/install-platformio.sh ================================================ #!/bin/bash echo "Installing Python Wheel ..." pip install wheel > /dev/null 2>&1 echo "Installing PlatformIO ..." pip install -U platformio > /dev/null 2>&1 echo "PlatformIO has been installed" echo "" function build_pio_sketch(){ # build_pio_sketch if [ "$#" -lt 3 ]; then echo "ERROR: Illegal number of parameters" echo "USAGE: build_pio_sketch " return 1 fi local board="$1" local sketch="$2" local buildFlags="$3" local sketch_dir=$(dirname "$sketch") echo "" echo "Compiling '"$(basename "$sketch")"' ..." python -m platformio ci -l '.' --board "$board" "$sketch_dir" --project-option="board_build.partitions = huge_app.csv" --project-option="build_flags=$buildFlags" } function count_sketches() # count_sketches { local examples="$1" rm -rf sketches.txt if [ ! -d "$examples" ]; then touch sketches.txt return 0 fi local sketches=$(find $examples -name *.ino) local sketchnum=0 for sketch in $sketches; do local sketchdir=$(dirname $sketch) local sketchdirname=$(basename $sketchdir) local sketchname=$(basename $sketch) if [[ "${sketchdirname}.ino" != "$sketchname" ]]; then continue fi; if [[ -f "$sketchdir/.test.skip" ]]; then continue fi echo $sketch >> sketches.txt sketchnum=$(($sketchnum + 1)) done return $sketchnum } function build_pio_sketches() # build_pio_sketches { if [ "$#" -lt 2 ]; then echo "ERROR: Illegal number of parameters" echo "USAGE: build_pio_sketches [ ]" return 1 fi local board=$1 local examples=$2 local chunk_idex=$3 local chunks_num=$4 if [ "$#" -lt 4 ]; then chunk_idex="0" chunks_num="1" fi if [ "$chunks_num" -le 0 ]; then echo "ERROR: Chunks count must be positive number" return 1 fi if [ "$chunk_idex" -ge "$chunks_num" ]; then echo "ERROR: Chunk index must be less than chunks count" return 1 fi set +e count_sketches "$examples" local sketchcount=$? set -e local sketches=$(cat sketches.txt) rm -rf sketches.txt local chunk_size=$(( $sketchcount / $chunks_num )) local all_chunks=$(( $chunks_num * $chunk_size )) if [ "$all_chunks" -lt "$sketchcount" ]; then chunk_size=$(( $chunk_size + 1 )) fi local start_index=$(( $chunk_idex * $chunk_size )) if [ "$sketchcount" -le "$start_index" ]; then echo "Skipping job" return 0 fi local end_index=$(( $(( $chunk_idex + 1 )) * $chunk_size )) if [ "$end_index" -gt "$sketchcount" ]; then end_index=$sketchcount fi local start_num=$(( $start_index + 1 )) echo "Found $sketchcount Sketches"; echo "Chunk Count : $chunks_num" echo "Chunk Size : $chunk_size" echo "Start Sketch: $start_num" echo "End Sketch : $end_index" local sketchnum=0 for sketch in $sketches; do local sketchdir=$(dirname $sketch) local sketchdirname=$(basename $sketchdir) local sketchname=$(basename $sketch) if [ "${sketchdirname}.ino" != "$sketchname" ] \ || [ -f "$sketchdir/.test.skip" ]; then continue fi local sketchBuildFlags="" if [ -f "$sketchdir/.test.build_flags" ]; then while read line; do sketchBuildFlags="$sketchBuildFlags $line" done < "$sketchdir/.test.build_flags" fi sketchnum=$(($sketchnum + 1)) if [ "$sketchnum" -le "$start_index" ] \ || [ "$sketchnum" -gt "$end_index" ]; then continue fi build_pio_sketch "$board" "$sketch" "$sketchBuildFlags" local result=$? if [ $result -ne 0 ]; then return $result fi done return 0 } ================================================ FILE: .github/scripts/on-push.sh ================================================ #!/bin/bash set -e if [ ! -z "$TRAVIS_BUILD_DIR" ]; then export GITHUB_WORKSPACE="$TRAVIS_BUILD_DIR" export GITHUB_REPOSITORY="$TRAVIS_REPO_SLUG" elif [ -z "$GITHUB_WORKSPACE" ]; then export GITHUB_WORKSPACE="$PWD" export GITHUB_REPOSITORY="me-no-dev/ESPAsyncWebServer" fi TARGET_PLATFORM="$1" CHUNK_INDEX=$2 CHUNKS_CNT=$3 BUILD_PIO=0 if [ "$#" -lt 1 ]; then TARGET_PLATFORM="esp32" fi if [ "$#" -lt 3 ] || [ "$CHUNKS_CNT" -le 0 ]; then CHUNK_INDEX=0 CHUNKS_CNT=1 elif [ "$CHUNK_INDEX" -gt "$CHUNKS_CNT" ]; then CHUNK_INDEX=$CHUNKS_CNT elif [ "$CHUNK_INDEX" -eq "$CHUNKS_CNT" ]; then BUILD_PIO=1 fi if [ "$BUILD_PIO" -eq 0 ]; then # ArduinoIDE Test source ./.github/scripts/install-arduino-ide.sh echo "Installing ESPAsyncWebserver ..." git clone https://github.com/me-no-dev/ESPAsyncWebServer "$ARDUINO_USR_PATH/libraries/ESPAsyncWebServer" echo "Installing ESP-StepperMotor-Server ..." cp -rf "$GITHUB_WORKSPACE" "$ARDUINO_USR_PATH/libraries/ESPAsyncWebServer" echo "Installing ESP-FlexyStepper ..." git clone https://github.com/pkerspe/ESP-FlexyStepper "$ARDUINO_USR_PATH/libraries/ESP-FlexyStepper" > /dev/null 2>&1 echo "Installing ArduinoJson ..." git clone https://github.com/bblanchon/ArduinoJson "$ARDUINO_USR_PATH/libraries/ArduinoJson" > /dev/null 2>&1 if [[ "$TARGET_PLATFORM" == "esp32" ]]; then echo "Installing AsyncTCP ..." git clone https://github.com/me-no-dev/AsyncTCP "$ARDUINO_USR_PATH/libraries/AsyncTCP" > /dev/null 2>&1 FQBN="espressif:esp32:esp32:PSRAM=enabled,PartitionScheme=huge_app" source ./.github/scripts/install-arduino-core-esp32.sh echo "BUILDING ESP32 EXAMPLES" else echo "Installing ESPAsyncTCP ..." git clone https://github.com/me-no-dev/ESPAsyncTCP "$ARDUINO_USR_PATH/libraries/ESPAsyncTCP" > /dev/null 2>&1 FQBN="esp8266com:esp8266:generic:eesz=4M1M,ip=lm2f" source ./.github/scripts/install-arduino-core-esp8266.sh echo "BUILDING ESP8266 EXAMPLES" fi build_sketches "$FQBN" "$GITHUB_WORKSPACE/examples" "$CHUNK_INDEX" "$CHUNKS_CNT" else # PlatformIO Test source ./.github/scripts/install-platformio.sh python -m platformio lib --storage-dir "$GITHUB_WORKSPACE" install echo "Installing ESP-FlexyStepper ..." python -m platformio lib -g install https://github.com/pkerspe/ESP-FlexyStepper.git > /dev/null 2>&1 echo "Installing ESPAsyncWebserver ..." python -m platformio lib -g install https://github.com/me-no-dev/ESPAsyncWebServer.git > /dev/null 2>&1 echo "Installing ArduinoJson ..." python -m platformio lib -g install https://github.com/bblanchon/ArduinoJson.git > /dev/null 2>&1 if [[ "$TARGET_PLATFORM" == "esp32" ]]; then BOARD="esp32dev" echo "Installing AsyncTCP ..." python -m platformio lib -g install https://github.com/me-no-dev/AsyncTCP.git > /dev/null 2>&1 echo "BUILDING ESP32 EXAMPLES" else BOARD="esp12e" echo "Installing ESPAsyncTCP ..." python -m platformio lib -g install https://github.com/me-no-dev/ESPAsyncTCP.git > /dev/null 2>&1 echo "BUILDING ESP8266 EXAMPLES" fi build_pio_sketches "$BOARD" "$GITHUB_WORKSPACE/examples" fi ================================================ FILE: .github/workflows/push.yml ================================================ name: ESP Async Web Server CI on: push: branches: - master - release/* pull_request: jobs: build-arduino: name: Arduino for ${{ matrix.board }} on ${{ matrix.os }} runs-on: ${{ matrix.os }} strategy: matrix: os: [ubuntu-latest, windows-latest, macOS-latest] board: [esp32] steps: - uses: actions/checkout@v1 - name: Build Tests run: bash ./.github/scripts/on-push.sh ${{ matrix.board }} 0 1 build-pio: name: PlatformIO for ${{ matrix.board }} on ${{ matrix.os }} runs-on: ${{ matrix.os }} strategy: matrix: os: [ubuntu-latest, windows-latest, macOS-latest] board: [esp32] steps: - uses: actions/checkout@v1 - name: Build Tests run: bash ./.github/scripts/on-push.sh ${{ matrix.board }} 1 1 ================================================ FILE: .gitignore ================================================ # Prerequisites *.d # Compiled Object files *.slo *.lo *.o *.obj # Precompiled Headers *.gch *.pch # Compiled Dynamic libraries *.so *.dylib *.dll # Fortran module files *.mod *.smod # Compiled Static libraries *.lai *.la *.a *.lib # Executables *.exe *.out *.app .pio .pioenvs .piolibdeps .travis.yml .vscode data ================================================ FILE: Documentation.md ================================================ # ESP-StepperMotor-Server This Library is ment for ESP32 modules for development in the Arduino or PlatfromIO IDE. It allows an easy configuration of an ESP32 based stepper motor control server. It provides multiple interfaces to configure and control 1-n stepper motors, that are connected to the ESP modules IO pins via stepper driver modules. Basically every stepper driver that provides an step and direction interface (IO Pins) can be controller with this library. The ESP-StepperMotor-Server starts a webserver with a user interface and also a REST API to configure and control stepper motor drivers as well as limit switches (homing and position switches) and software controled emergency shutdown switches. Also supports rotary encoders to control the position of connected stepper motors. For more details visit the ESP-StepperMotor-Server [github repository](https://github.com/pkerspe/ESP-StepperMotor-Server) and check out the detailed [README.md](https://github.com/pkerspe/ESP-StepperMotor-Server/blob/master/README.md) file. Copyright (c) 2019 Paul Kerspe - Licensed under the [MIT license](https://github.com/pkerspe/ESP-StepperMotor-Server/blob/master/LICENSE.txt). ================================================ FILE: LICENSE.txt ================================================ MIT License Copyright (c) 2019 Paul Kerspe Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions: The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. ================================================ FILE: README.md ================================================ # ESP-StepperMotor-Server - A stepper motor control server running on ESP32 modules [![Codacy Badge](https://api.codacy.com/project/badge/Grade/d9bf5e50c7334b71a9dfba7367b3b18e)](https://app.codacy.com/manual/pkerspe/ESP-StepperMotor-Server?utm_source=github.com&utm_medium=referral&utm_content=pkerspe/ESP-StepperMotor-Server&utm_campaign=Badge_Grade_Dashboard) Turn your ESP32 into a standalone stepper motor control server with easy to use webinterface. Connect one or more stepper drivers with step and direction input, and optionally some limit-switches to the IO-pins of your ESP module and control the stepper motor via a comfortable web interface, via REST API or via a serial control interface. ## Table of contents * [Introduction](#introduction) * [What this library is NOT](#what-this-library-is-not) * [Prerequisites and dependencies](#prerequisites-and-dependencies) * [Setting up your ESP-StepperMotor-Server](#Setting-up-your-ESP-StepperMotor-Server) * [Firmware installation](#Firmware-installation) * [Using Arduino IDE](#using-arduino-ide) * [Using PlatformIO](#using-platformio) * [Reducing code size](#reducing-code-size) * [Installation of the web user interface](#installation-of-the-web-ui) * [Connecting the hardware](#connecting-the-hardware) * [Connecting rotary encoders](#connecting-rotary-encoders) * [Configuration via the web user interface](#configuration-via-the-web-user-interface) * [Other UI masks](#other-ui-masks) * [The OTA Fimware Update function](#the-ota-fimware-update-function) * [The self-test page](#the-self-test-page) * [API Documentation](#api-documentation) * [Library API documentation](#library-api-documentation) * [REST API documentation](#rest-api-documentation) * [Serial command line interface (CLI)](#Serial-command-line-interface) * [Further documentation](#further-documentation) * [License](#license) | ESP StepperMotor Server start screen | ESP StepperMotor Server start screen | ESP StepperMotor Server start screen | ESP StepperMotor Server REST API documentation screen | | --- | --- | --- | --- | | home screen | configuration screen | control screen | REST API doucmentation | ## Introduction This library started as a fork for the [FlexyStepper library](https://github.com/Stan-Reifel/FlexyStepper). While the FlexyStepper Library is a general Arduino compatible library this fork had a focus on the ESP32 modules from Espressif. Soon this library became much more than a modfied version of FlexyStepper but turned into a stand-alone application to turn a regular ESP32 module into a stepper motor control server. The core part that controls the stepper motor drivers is now based on a modified version of FlexyStepper, called [ESP-FlexyStepper](https://github.com/pkerspe/ESP-FlexyStepper). Since the ESP-32 modules contain a WIFI module they are perfectly suited for web-controlled stepper server and since they have enough memory and processing power, they are ideal as low cost, low energy consumption standalone server component, that allows configuration and controlling of one to many stepper motor drivers with limit-switches and outputs (e.g. for Relays and LEDs). Once the ESP Stepper Motor Server has been uploaded to the ESP module, all further configuration and controlling can be done vie the web UI without the need to code another line in the Arduino or PlatformIO IDE. ### What this library is NOT This library is not ideal if you are looking for a solution to control your CNC Router. It does not support Gerber commands (GRBL) in general or fully synchronized multi axis movements (it can move multiple axis at the same time though since it generates all step signals for all connected stepper drivers asynchronous). If you need a solution for you CNC project, you might want to look into the [Grbl_Esp32](https://github.com/bdring/Grbl_Esp32) (for ESP32 specifically) or [grbl](https://github.com/gnea/grbl) (for Arduino in general) Libraries. But if you are looking for an easy way to setup and control one or more stepper motors independently and adding limit switches and rotary encoders to control them, then this project here might be just what you are looking for. ### Prerequisites and dependencies In order to compile your project with the ESP-StepperMotor-Server Library, the following 3rd party extensions need to be installed on your system (if you use PlatformIO all needed dependencies will be installed for you when you follow the instructions in the [Using PlatformIO](#using-platformio) section above): * [ESPAsyncWebserver](https://github.com/me-no-dev/ESPAsyncWebServer) * [AsyncTCP](https://github.com/me-no-dev/AsyncTCP) * [ArduinoJSON (NOTE: must version 6.x, version 5 will not work)](https://arduinojson.org) * [ESP-FlexyStepper](https://github.com/pkerspe/ESP-FlexyStepper) * FS file system wrapper: should be installed with the ESP32 libraries already if you setup your IDE for these modules * WIFI: should be installed with the ESP32 libraries already when you setup your IDE for these modules When using PlatformIO add these dependencies to you platformio.ini project file and let PlatformIO install the required dependencies for you: ```ini lib_deps = ESP-StepperMotor-Server ``` When using Arduino, you need to install these libraries using the Library Manager. If you use PlatformIO you can simply setup your project with the provided paltformio.ini file in this repository ## Setting up your ESP-StepperMotor-Server To get started you need the following elements: * An *ESP32* board of your choice (boards with USB-Serial Chips are recommended for the ease of programming them, other boards just work as well, yet you have to figure out how to flash the firmware yourself, since this process will not be covered in this manual) * A configured, Arduino compatible IDE ([Arduino](https://www.arduino.cc/en/Main/Software) or [PlatformIO](http://platformio.org)) * A *stepper motor* * A *power supply* that fits to your stepper motors and drivers' specs * A *stepper driver* board that fits to your stepper motors specs Optional: * Switches for limit/homing, position and emergency stop functionality * Rotary encoders to control the motors directly using physical controls ### Firmware installation #### Using Arduino IDE USING ARDUINO IDE IS NOT SUGGESTED due to multiple issues with the dependencies and much higher manual effort to get everything running. If you still want to try it, the following steps might work, but you are basically on your own here. Do yourself a favor and use a real IDE like Visual Studio Code with PlatformIO (it is free and way more comfortable and powerful than the Arduino IDE) :-) 1. Download and install the [Arduino IDE](https://www.arduino.cc/en/main/software) 2. open the library manager and search for "ESP-StepperMotor-Server", select the latest version and click on "install" 3. if asked to install the required dependencies confirm to install all dependencies as well 4. if dependency installation fails install the following dependencies manually: * ArduinoJSON (the one from Benoit Blanchon) * ESP-FlexyStepper * at the time of writing this documentation, the following two libraries are not available via the library manager, so they need to be installed manually, if you cannot find them in the library manager: * ESPAsyncWebServer: [https://github.com/me-no-dev/ESPAsyncWebServer](https://github.com/me-no-dev/ESPAsyncWebServer) * AsyncTCP [https://github.com/me-no-dev/AsyncTCP](https://github.com/me-no-dev/AsyncTCP) #### Using PlatformIO [PlatformIO](http://platformio.org) is an open-source ecosystem for IoT development with cross platform build system, library manager and full support for Espressif ESP32 development. It is based on the free Visual Studio Code from Microsoft, but still works on most popular host OS: Mac OS X, Windows, Linux 32/64, Linux ARM (like Raspberry Pi, BeagleBone, CubieBoard). 1. Install [PlatformIO IDE](http://platformio.org/platformio-ide) 2. Create new project using "PlatformIO Home > New Project" 3. Add "ESP-StepperMotor-Server" to the project using [Project Configuration File `platformio.ini`](http://docs.platformio.org/page/projectconf.html) and [lib_deps](http://docs.platformio.org/page/projectconf/section_env_library.html#lib-deps) option. Here is an example platformio.ini file you can use for an ESP32 based module with ESP-StepperMotor-Server: ```ini [env:esp32dev] platform = espressif32 board = esp32dev framework = arduino lib_deps = ESP-StepperMotor-Server monitor_speed = 115200 ``` 5. now you can open the main.cpp file and include the ESP-StepperMotor-Server and create an instance of the server with a minimal configuration that connects to an existing WIFI like this: ```#include #include ESPStepperMotorServer *stepperMotorServer; const char *wifiName= ""; // enter the SSID of the wifi network to connect to const char *wifiSecret = ""; // enter the password of the the existing wifi network here void setup() { Serial.begin(115200); stepperMotorServer = new ESPStepperMotorServer(ESPServerRestApiEnabled | ESPServerWebserverEnabled | ESPServerSerialEnabled); stepperMotorServer->setWifiCredentials(wifiName, wifiSecret); stepperMotorServer->setWifiMode(ESPServerWifiModeClient); //start the server as a wifi client (DHCP client of an existing wifi network) stepperMotorServer->start(); } void loop() { } ``` *NOTE:* Replace `` with the name of your WiFI and `` with your WIFI password in the example code above This is the absolute minimum example how to start the server. For further examples and more inline documentation see the provided example sketches. 6. [Build/compile and upload the project](http://docs.platformio.org/en/latest/tutorials/espressif32/arduino_debugging_unit_testing.html#compiling-and-uploading-the-firmware) to your connected ESP32 module and open the console Monitor in PlatformIO (or connect to the board using your prefered serial terminal console) to see the output of the ESP-StepperMotor-Server starting up. In the output on the serial monitor you should see that some output similar to this: ```[INFO] Loading configuration file /config.json from SPIFFS [INFO] 2 stepper configuration entries loaded from config file [INFO] 2 switch configuration entries loaded from config file [INFO] 2 rotary encoder configuration entries loaded from config file [INFO] Starting ESP-StepperMotor-Server (v. 0.0.6) [INFO] Trying to connect to WIFI with SSID '' .... [INFO] Connected to network with IP address XXX.XXX.XXX.XXX ... [INFO] Starting webserver on port YY [INFO] Webserver started, you can now open the user interface on http://XXX.XXX.XXX.XXX:YY/ ... ``` During Startup the ESP32 will check if the User Interface is installed on the ESP32s SPI Flash File System (SPIFFS). If it cannot find one or more required files it will attempt to download the files via the WIFI connection from the github repository (if the SPIFFS has been initialized at least once before). More Details can be found in the section [Installation of the Web UI](#insallation-of-the-web-ui) Once the UI is installed on the SPIFFS you should see the following (or a similar) output in the serial console after the Wifi Connection has been established: ```[INFO] Listing files in root folder of SPIFFS: [INFO] File: /index.html (615) -1 [INFO] File: /js/app.js.gz (266875) -1 [INFO] File: /img/rotaryEncoderWheel.svg (13750) -1 [INFO] File: /img/stepper.svg (22739) -1 [INFO] File: /img/switch.svg (19709) -1 [INFO] File: /img/logo.svg (25066) -1 [INFO] File: /favicon.ico.gz (1565) -1 ``` Now that the server has started, you can open the UI in a browser on your PC connected to the same WIFI network, by typing the IP Address you saw in the serial console before into the address bar of your browser prefixed with "http://". You should now see the start screen of the ESP StepperMotor Server: ![startup screen][startup_screen] ### Reducing code size When you build the ESP-StepperMotor-Server without any optimizations it takes up a fair amount of the ESP32s flash size (in the standard OTA partition layout). If you do not need all modules of the ESP-StepperMotor-Server you can use build flags to reduce the code size significantly. The following build flags are supported: * ```ESPStepperMotorServer_COMPILE_NO_WEB```: using this flag completely disables the Web Interface, the REST API and the Websocket server. This has the biggest impact on the compiled size, since it also affects the inclusion of the external dependencies of the ESP Async WebServer and AsyncTCP libraries. If you use this flag, you will not be able to use the webinterface of the ESP Stepper motor server anymore for configuration and control of the server. You can then only interact with the server using the serial command line interface * ```ESPStepperMotorServer_COMPILE_NO_DEBUG```: this flag will remove all debug output and debug functions, leading to a small reduction of the size * ```ESPStepperMotorServer_COMPILE_NO_CLI_HELP```: this flag will remove all help texts from the Command line interface help command and by that reducing the size a bit further The following chart shows the impact on file size when disabling one or more features (numbers base on a rather small main program as provided in the examples folder and are also just a guideline since these statistics have been create with version 0.4.6, due to changes in the dependency libraries but also due to new features in this library itself, the overall size might increase or decrease): ![compiled size][compiled_size] To use one or more of these build flags in PlatformIO, simply add the following line to your `platformio.ini` file of your project (e.g. to disable debug output and the help texts in the Command Line Interface): ``` build_flags = -D ESPStepperMotorServer_COMPILE_NO_DEBUG -D ESPStepperMotorServer_COMPILE_NO_CLI_HELP ``` ### Installation of the Web UI Once you uploaded the compiled sketch to your ESP32 (don't forget to enter your SSID and WIFI Password in the sketch!) the ESP will connect to the WIFI with the specified SSID and check if the UI files are already installed in the SPI Flash File System (SPIFFS) of the ESP. If not, it will try to download it. In case your WIFI does not provide an open internet connection, you need to upload the files manually using he "Upload File System image" task from PlatformIO. Make sure your `data` folder in your platformIO project exists and contains the required files and folders for the User Interface. You can find all UI files in a separate GitHub repository for the User Interface: https://github.com/pkerspe/ESP-StepperMotor-Server-UI/tree/master/data Hint: If you want to customize the user interface of the Stepper Motor Server, you can clone the [repository](https://github.com/pkerspe/ESP-StepperMotor-Server-UI) and modify the User interface that is based on vue.js and build your own version using `npm run build` and then copy the output to the data folder of your ESP32 Stepper Motor Server project. Once all is done you can enter the IP address of you ESP32 module in the browser and you will see the UI of the Stepper Motor Server, where you can configure the stepper motors and controls. To figure out the IP address of your ESP-32 module, you can either check your routers admin UI or you can connect to the serial port of the ESP-32 and check the output. Once the connection to you WIFI has been established, the module will print the IP address to the serial console. ### Connecting the hardware The following wiring chart shows an example of a setup with an optional emergency/kill switch and two optional homing/limit switches. In a real setup, the homing switches would be attached for example to each end of a linear rail to detect when the object moved by the stepper motor reaches the end of the track. *NOTE:* in the below wiring diagram the ENABLE pin of the driver is connected to +5V, you need to check your driver if this is required or actually correct. Some drivers are DISABLED if a high signal is present on the ENABLE pin! ![hardware example setup][connection_setup_example] (image created with [fritzing](https://fritzing.org/home/)) ### Connecting rotary encoders to connect a rotary encoder, you need to free IO Pins, one for the A and one for the B pin of your encoder. The common pin on the rotary encoder needs to be connected to ground. The specified IO Pins on the ESP32 will be configured as INPUT with internal pull-up resistor automatically. PLEASE NOTE: once you turn the rotary encoder the current stepper position of the connected stepper motor will be incremented/decremented by the number of steps you configured in the multiplier field and set as the new target position. This might not be what you want it to behave, but currently it is the way it is developed. I might implement an additional option that will allow you to increase/decrease the current target position of the stepper motor with each increment on the rotary encoder. Simply spoken: no matter how quick you turn the rotary encoder it will always just cause the stepper to move a number of configured steps from its CURRENT physical position when the last signal from the rotary encoder has been received. For now, you could change this behavior by changing the following lines in the ESPStepperMotorServer.cpp file: `stepperConfig->_flexyStepper->setTargetPositionRelativeInSteps(1 * rotaryEncoder->_stepMultiplier);` to `stepperConfig->_flexyStepper->setTargetPositionInSteps(stepperConfig->_flexyStepper->getTargetPositionInSteps() + 1 * rotaryEncoder->_stepMultiplier);` and the line `stepperConfig->_flexyStepper->setTargetPositionRelativeInSteps(newPosition);` to `stepperConfig->_flexyStepper->setTargetPositionInSteps(stepperConfig->_flexyStepper->getTargetPositionInSteps() + newPosition);` ### Configuration via the web user interface After you installed everything on the hardware side, you can open the web UI to setup/configure the server. In the navigation on the left side click on "SETUP" to open the configuration page. The following devices can be configured: * Stepper Motors (or to be more precise "connected stepper drivers") * Switches (input signals in general): multiple types of functions are supported for the switches * [Limit](https://en.wikipedia.org/wiki/Limit_switch)/Homing Switches * Position Switches * emergency stop / [kill switches](https://en.wikipedia.org/wiki/Kill_switch) * in future versions also switches to trigger movement macros will be supported * [Incremental rotary encoders](https://en.wikipedia.org/wiki/Incremental_encoder) as control inputs to control the configured steppers via physical controls (you can always use the web interface or serial control commands directly to control the stepper motor position, speed etc.) ![startup screen][add_stepper_dialog] ![startup screen][add_switch_dialog] ![startup screen][add_rotary_encoder_dialog] ## Other UI masks Besides the regular UI views to configure the ESP-StepperMotorServer there are currently to other view you can call directly via specific paths: ### The OTA Firmware Update function When entering the URL `http://:/update` you will see the Dialog to update the firmware of the ESP-StepperMotorServer over the air (OTA). Once you have the Firmware transferred to your ESP32 initially via the physical connection you do not need to reconnect it to your computer for future updates. You can always use the OTA update function to write new versions of the firmware via WIFI the connection. For further details on how to create the needed firmware file please refer to your IDE and build chain documentation. *NOTE: to be able to use OTA you need to make sure that you use a flash partition pattern that allows for OTA update. Usually this is the default partition in most IDE settings, so unless you changed the partitioning manually you should be fine anyway.* ### The self-test page When entering the URL `http://:/selftest` you will get to a page that outputs information on your current setup / installation status of the ESP-StepperMotorServer. This page is basically for trouble shooting and will be extended over time. Whenever you have any issues with your installation you might want to check this page to see if any errors are shown here. Currently it will output information mainly about the SPIFFS (SPI-Flash-Filesystem) status, since it seems to be a common cause for problems according to the issue list on this project. Thus, you should check it to see if any negative results are displayed. ## API documentation ### Library API documentation The library is designed with ease of use and flexibility of the configuration options in mind. You can configure the server completely in your code or you can just use the basic example code and perform all further configuration in the Web user interface using your browser. Here is an overview of the most important API calls, in case you want to go down the road of customizing and configuration within you sketch: *class ESPStepperMotorServer* this is the main class and the one you want to start with. |function|description|parameters| |----|----|----| |`ESPStepperMotorServer(byte serverMode, byte logLevel)`|constructor to create a new instance of the server. Note: Do not create more than one instance of the server in your code, to prevent issues with the interrupt service routines that are used by the server to listen to inputs.|`byte serverMode`: specify which modules of the server shall be started. Currently three modules are supported: the web interface, the REST API and the serial console control interface. The web interface relies on the REST API, so it should not be enabled without the REST API. If you do not want to connect to a WIFI or start your own AP the serial console is the only way to interact with the server. Use the constants ESPServerRestApiEnabled, ESPServerWebserverEnabled and ESPServerSerialEnabled to decide which modules to enable. e.g. `stepperMotorServer = new ESPStepperMotorServer(ESPServerRestApiEnabled | ESPServerWebserverEnabled | ESPServerSerialEnabled);`

`byte logLevel`: *optional* parameter to set the log level during instantiation. Default is INFO. Use one of `ESPServerLogLevel_DEBUG`, `ESPServerLogLevel_INFO`, `ESPServerLogLevel_WARNING`| |`void setHttpPort(int portNumber)`|Set the http port number on which the server should list for requests for the web interface and the REST API. Only used if the server is started in the ESPServerWebserverEnabled or ESPServerRestApiEnabled (or both) mode|`int portNumber`: the port number to start the webserver on. Only needed if the ESPServerRestApiEnabled or ESPServerWebserverEnabled module is enabled. Default port is 80| |`void setAccessPointName(const char *accessPointSSID)`|Set the name of the Access Point (SSID) to create by the server|`const char *accessPointSSID`: the name of the access point to open up. Only used when the server is configured to start in AP mode by using `setWifiMode(ESPServerWifiModeAccessPoint)` is used. The default value is 'ESP-StepperMotor-Server'| |`void setAccessPointPassword(const char *accessPointPassword)`|Set the password needed to connect to the Access Point created by the server. Only used when the server is configured to start in AP mode by using `setWifiMode(ESPServerWifiModeAccessPoint)` is used. The default value is 'Aa123456'|`const char *accessPointPassword`| |`void setWifiCredentials(const char *ssid, const char *pwd)`|Set the wifi credentials for your local WIFI to connect to. Only used when the server is configured in WIFI Client mode by using `setWifiMode(ESPServerWifiModeClient)`|`const char *ssid`: the name of the WIFI to connect to. `const char *pwd`: the password for the WIFI to connect to| |`void setWifiMode(byte wifiMode)`|Set the WIFI mode to start the server in. It can either operate in WIFI Client or Access Point mode. As a client it connects to an existing WIFI network. Requires the WIFI access credentials to be set using the `setWifiCredentials` function. In Access Point mode, the server opens it's own WIFI network and waits for clients to connect. You can specify the AP Name and Password using the `setAccessPointName` and `setAccessPointPassword` functions (otherwise default values will be used, for details see documentation of the mentioned functions and parameters)|`byte wifiMode`: the mode to use. Supported values should be provided with the constants `ESPServerWifiModeClient` and `ESPServerWifiModeAccessPoint`. To disable the WIFI modes completely use `ESPServerWifiDisabled`| |`void setStaticIpAddress(IPAddress staticIP, IPAddress gatewayIP, IPAddress subnetMask, IPAddress dns1, IPAddress dns2)`|Set a static IP Address, gateway IP and subnet mask. The primary and secondary DNS Server arguments are optional and can be omitted| |`void printWifiStatus()`|prints current WIFI connection details to the serial console. This should be called only AFTER the server has been started, since the connection to the WIFI network or setup of an Access Point is only done after calling the `start()` function of the server|none| |`int addOrUpdateStepper(ESPStepperMotorServer_StepperConfiguration *stepper, int stepperIndex = -1)`|Add a new stepper motor to the server configuration or update an existing one with a given id. This function returns the ID of the newly created stepper configuration for further reference. If an existing configuration has been updated, the id of the updated configuration is returned (same as provided `stepperIndex` parameter value)|`ESPStepperMotorServer_StepperConfiguration *stepper,`: pointer to a configured `ESPStepperMotorServer_StepperConfiguration` instance. Optional `int stepperIndex`: if set this parameter indicates the configuration ID of an existing stepper configuration, that shall be overwritten/replace with the new one supplied using the `stepper` parameter| |`int addOrUpdatePositionSwitch(ESPStepperMotorServer_PositionSwitch *posSwitchToAdd, int switchIndex = -1)`|Add a new position switch to the server configuration or update an existing one with a given id. This function returns the ID of the newly created position switch configuration for further reference. If an existing configuration has been updated, the id of the updated configuration is returned (same as provided `switchIndex` parameter value)|`ESPStepperMotorServer_PositionSwitch *posSwitchToAdd,`: pointer to a configured `ESPStepperMotorServer_PositionSwitch` instance. Optional `int switchIndex`: if set this parameter indicates the configuration ID of an existing switch configuration, that shall be overwritten/replace with the new one supplied using the `posSwitchToAdd` parameter| |`int addOrUpdateRotaryEncoder(ESPStepperMotorServer_RotaryEncoder *rotaryEncoder, int encoderIndex = -1)`|Add a new rotary encoder to the server configuration or update an existing one with a given id. This function returns the ID of the newly created encoder configuration for further reference. If an existing configuration has been updated, the id of the updated configuration is returned (same as provided `encoderIndex` parameter value)|`ESPStepperMotorServer_RotaryEncoder *rotaryEncoder,`: pointer to a configured `ESPStepperMotorServer_RotaryEncoder` instance. Optional `int encoderIndex`: if set this parameter indicates the configuration ID of an existing encoder configuration, that shall be overwritten/replace with the new one supplied using the `rotaryEncoder` parameter| |`void removePositionSwitch(int positionSwitchIndex)`|Remove/Delete a previously configured position switch|`int positionSwitchIndex`: the id of the configuration to delete| |`void removeStepper(byte stepperConfigurationIndex)`|Remove/Delete a previously configured stepper motor|`int stepperConfigurationIndex`: the id of the configuration to delete| |`void removeRotaryEncoder(byte rotaryEncoderConfigurationIndex)`|Remove/Delete a previously configured encoder|`int rotaryEncoderConfigurationIndex`: the id of the configuration to delete| |`void printPositionSwitchStatus()`|Print the current switch status to the serial console as JSON formatted string. This contains detailed information for each registered switch along with its current status. e.g. `{"settings":{"positionSwitchCounterLimit":10,"statusRegisterCounter":2},"switchStatusRegister":[{"statusRegisterIndex":0,"status":"00000000"},{"statusRegisterIndex":1,"status":"00000000"}],"positionSwitches":[{"id":0,"name":"Limit 1 X-Axis","ioPin":14,"position":-1,"stepperId":0,"active":1,"type":{"pinMode":"Active Low"}},{"id":1,"name":"Limit 2 X-Axis","ioPin":15,"position":200000,"stepperId":1,"active":1,"type":{"pinMode":"Active Low"}}]}`|none| |`void start()`|start the ESP-StepperMotor-Server. Calling this function lets all the magic begin. Depending on the configuration this includes the following tasks: starting the webserver, starting the REST API, starting the serial console command interface, setting up the configured IO pins, registering interrupt handlers for all switches and rotary encoders and printing out a whole bunch of information on the serial console to inform you about the progress of the startup sequence|none| |`void stop()`|start the ESP-StepperMotor-Server. Basically un-do all the stuff that has been done during the start-up sequence|none| |`byte getPositionSwitchStatus(int positionSwitchIndex)`|Get the switch status of a specific switch. Return 1 if the switch is currently triggered, 0 if it is not|`int positionSwitchIndex`| |`void getButtonStatusRegister(byte buffer[ESPServerSwitchStatusRegisterCount])`|Populate the given byte buffer with the switch status for each configured button (1 = button is triggered, 0 = button is not triggered)|`byte buffer[]`: a byte array to populate with the status register contents for all configured switches (basically the current switch status in regards to being active/inactive)| |`String getIpAddress()`|get the current IP address of the server. Only Available if connected to a WIFI or if started in AP mode|none| |`ESPStepperMotorServer_Configuration *getCurrentServerConfiguration()`|get the pointer of the ESPStepperMotorServer_Configuration instance that represents the current server complete configuration|none| |`ESPStepperMotorServer_CLI *getCLIHandler() const`|get the pointer of the serial CLI handler instance. This can be used to register custom CLI commands.|none| ### REST API documentation Besides the web-based User Interface the ESP StepperMotor Server offers a REST API to control all aspects of the server that can also be controlled via the web UI (in fact the web UI uses the REST API for all operations). The following is an excerpt of the endpoints being provided: | METHOD | PATH | DESCRIPTION | |---|---|---| |GET |`/api/status`|get the current stepper server status report including the following information: version string of the server, wifi information (wifi mode, IP address), spiffs information (total space and free space)| |POST |`/api/steppers/returnhome`|endpoint to trigger homing of the stepper motor. This is a non-blocking call, meaning the API will directly return even though the stepper motor is still performing the homing movement.

*IMPORTANT:* this function should only be called if you previously configured a homing / limit switch for this stepper motor, otherwise the stepper will start jogging for a long time (a default limit of 2000000000 steps is configured, but can be overwritten with a POST parameter) before coming to a halt.

*Required post parameters:*
__id__: the id of the stepper motor to perform the homing command for)
__speed__: the speed in steps per second to perform the homing command with

*Optional POST parameters:*
__switchId__: define the configuration id of the position switch to use as limit switch. __NOTE__: this switch should be assigned to the stepper motor, so you should not provide the id of a position switch that is not linked to the stepper driver defined in the mandatory __id__ parameter. Ideally the switch is also configured as a limit type switch.
__direction__: the homing direction for the stepper movement. Could be either 1 or -1. If parameter is not given the direction will be determined from the limit switch configuration (depending on the switch type "begin" or "end")
__accel__: the acceleration for the homing procedure in steps/sec^2, if omitted the previously defined acceleration in the flexy stepper instance will be used
__maxSteps__: this parameter defines the maximum number of steps to perform before cancelling the homing procedure. This is kind of a safeguard to prevent endless spinning of the stepper motor. Defaults to 2000000000 steps| |POST|`/api/steppers/moveby`|endpoint to set a new RELATIVE target position for the stepper motor in either mm, revs or steps. Required post parameters: id, unit, value. Optional post parameters: speed, acel, decel| |POST |`/api/steppers/position`|endpoint to set a new absolute target position for the stepper motor in either mm, revs or steps. Required post parameters: id, unit, value. Optional post parameters: speed, acel, decel| | GET |`/api/steppers` or `/api/steppers?id=`|endpoint to list all configured steppers or a specific one if "id" query parameter is given |DELETE|`/api/steppers?id=`|delete an existing stepper configuration entry| |POST |`/api/steppers`|add a new stepper configuration entry| | PUT|`/api/steppers?id=`|update an existing stepper configuration entry| | GET |`/api/switches/status` or `/api/switches/status?id=`|get the current switch status (active, inactive) of either one specific switch or all switches (returned as a bit mask in MSB order)| | GET |`/api/switches` or `/api/switches?id=`|endpoint to list all position switch configurations or a specific configuration if the "id" query parameter is given| | POST |`/api/switches`|endpoint to add a new switch configuration| | PUT |`/api/switches?id=`|endpoint to update an existing switch configuration| | DELETE |`/api/switches?id=`|delete a specific switch configuration| | GET |`/api/config`|get the JSON representation of the current server configuration with all configured steppers, switches and encoders. This is the in-memory configuration (current is-state) which might differ from the persisted configuration. To persist the current configuration see `GET /api/config/save`| | GET |`/api/config/save`|save the current in-memory configuration of the server to the [SPIFFS](https://docs.espressif.com/projects/esp-idf/en/latest/esp32/api-reference/storage/spiffs.html) into the `config.json` file. You can download this file using the URL schema `http://:/config.json`. Calling this endpoint persists the configuration in its current state to survive also power loss / reboot / reset of the server. This should be called whenever you perform any changes on the configuration that you want to keep even after a reboot/reset of the ESP| To get a full list of endpoints navigate to the about page in the web UI and click on the REST API documentation link ![about screen][about_screen] ### Serial command line interface Once started, the stepper server offers a CLI (command line interface) on the serial port to control most of the functions that can also be controlled via the web interface or REST API and some additional functions. Once the server is started (and the CLI has not been disabled in the constructor) you will see some log output on the console and also the following line: `[INFO] Command Line Interface started, registered XX commands. Type 'help' to get a list of all supported commands` Now you can input commands via the serial port. To get a list of all available commands type `help` in the serial console and press enter. The output should look like this (depending on the version and how up2date this manual is, you might see some more commands): ````-------- ESP-StepperMotor-Server-CLI Help ----------- The following commands are available: []: Built in commands: help [h]: show a list of all available commands moveby [mb]*: move by a specified number of units. requires the id of the stepper to move, the amount of movement and also optional the unit for the movement (mm, steps, revs). If no unit is specified steps will be assumed as unit. Optionally you can also set the speed in steps/second, acceleration and deceleration, each in steps/second/second). Set speeds, acceleration and deceleration are rememebered until overwritten again. E.g. mb=0&v:-100&u:mm&s:200 to move the stepper with id 0 by -100 mm with a speed of 200 steps per second moveto [mt]*: move to an absolute position. requires the id of the stepper to move, the amount of movement and also optional the unit for the movement (mm, steps, revs). If no unit is specified steps will be assumed as unit. Optionally you can also set the speed in steps/second, acceleration and deceleration, each in steps/second/second). Set speeds, acceleration and deceleration are rememebered until overwritten again. E.g. mt=0&v:100&u:revs&a:100 to move the stepper with id 0 to the absolute position at 100 revolutions with an acceleration of 100 steps per second^2 config [c]: print the current configuration to the console as JSON formatted string emergencystop [es]: trigger emergency stop for all connected steppers. This will clear all target positions and stop the motion controller module immediately. In order to proceed normal operation after this command has been issued, you need to call the `revokeemergencystop` [res] command revokeemergencystop [res]: revoke a previously triggered emergency stop. This must be called before any motions can proceed after a call to the emergency-stop command position [p]*: get the current position of a specific stepper or all steppers if no explicit index is given (e.g. by calling 'pos' or 'pos=&u:mm'). If no parameter for the unit is provided, will return the position in steps. Requires the ID of the stepper to get the position for as parameter and optional the unit using 'u:mm'/'u:steps'/'u:revs'. E.g.: p=0&u:steps to return the current position of stepper with id = 0 with unit 'steps' velocity [v]*: get the current velocity of a specific stepper or all steppers if no explicit index is given (e.g. by calling 'pos' or 'pos=&u:mm'). If no parameter for the unit is provided, will return the position in steps. Requires the ID of the stepper to get the velocity for as parameter and optional the unit using 'u:mm'/'u:steps'/'u:revs'. E.g.: v=0&u:mm to return the velocity in mm per second of stepper with id = 0 removeswitch [rsw]*: remove an existing switch configuration. E.g. rsw=0 to remove the switch with the ID 0 removestepper [rs]*: remove and existing stepper configuration. E.g. rs=0 to remove the stepper config with the ID 0 removeencoder [re]*: remove an existing rotary encoder configuration. E.g. re=0 to remove the encoder with the ID 0 reboot [r]: reboot the ESP save [s]: save the current configuration to the SPIFFS in config.json stop [st]: stop the stepper server (also stops the CLI!) loglevel [ll]*: set or get the current log level for serial output. valid values to set are: 1 (Warning) - 4 (ALL). E.g. to set to log level DEBUG use sll=3, to get the current log-level call without any parameter serverstatus [ss]: print status details of the server as JSON formatted string switchstatus [pss]: print the status of all input switches as JSON formatted string setapname [san]*: set the name of the access point to be opened up by the esp (if in AP mode) setappwd [sap]*: set the password for the access point to be opened by the esp sethttpport [shp]*: set the http port to listen for for the web interface setwifissid [sws]*: set the SSID of the WIFI to connect to (if in client mode) setwifipwd [swp]*: set the password of the Wifi network to connect to") commands marked with a * require input parameters. Parameters are provided with the command separated by a = for the primary parameter. Secondary parameters are provided in the format '&:=&:` An example for a command with multiple parameters is the `moveto` command. The shortcut for this command is `mt`. The command supports six parameters: the id of the stepper to move (primary parameter), the amount/value for the movement (v parameter), the unit (u parameter) for the movement (mm, steps or revolutions), the speed (s parameter) in steps per second, the acceleration (a parameter) in steps per second per second and the deceleration (d parameter) in steps per second per second. Example: If you want to move the configured stepper motor with the id 0 by 10 revolutions with a speed of 100 steps per second the command looks as follows: `mt=0&v:10&u:revs&s:100` ### Further documentation for further details have a look at * the provided example files / projects in the [examples folder](https://github.com/pkerspe/ESP-StepperMotor-Server/tree/master/examples) of this repository ## License Copyright (c) 2019 Paul Kerspe - Licensed under the MIT license. [startup_screen]: https://github.com/pkerspe/ESP-StepperMotor-Server/raw/master/doc/images/server_startup_screen.png "ESP StepperMotor Server startup screen" [add_stepper_dialog]: https://github.com/pkerspe/ESP-StepperMotor-Server/raw/master/doc/images/add_stepper_config_dialog.png "The dialog to add a new stepper motor configuration" [add_switch_dialog]: https://github.com/pkerspe/ESP-StepperMotor-Server/raw/master/doc/images/add_switch_dialog.png "The dialog to add a new switch (input signal) configuration" [add_rotary_encoder_dialog]: https://github.com/pkerspe/ESP-StepperMotor-Server/raw/master/doc/images/add_rotary_encoder_dialog.png "The dialog to add a new rotary encoder to control a stepper" [about_screen]: https://github.com/pkerspe/ESP-StepperMotor-Server/raw/master/doc/images/about_screen.png "The about screen with the link to the REST API documentation" [connection_setup_example]: https://github.com/pkerspe/ESP-StepperMotor-Server/raw/master/doc/images/connection_setup_example.png "Example setup wiring diagram" [compiled_size]: https://github.com/pkerspe/ESP-StepperMotor-Server/raw/master/doc/images/compiled_size.png "Compile size comparison of different build options" ================================================ FILE: examples/Example1_BasicESPStepperMotorServer/Example1_BasicESPStepperMotorServer.ino ================================================ // ****************************************************************** // * Simple example for starting the stepper motor server * // * Paul Kerspe 31.5.2020 * // ****************************************************************** // // This is the simplest example of how to start the ESP Stepper Motor Server with the Webinterface to perform all setup steps via the Web UI // // This library requires that your stepper motor be connected to the ESP32 // using an external driver that has a "Step and Direction" interface. // // For all driver boards, it is VERY important that you set the motor // current before running the example. This is typically done by adjusting // a potentiometer on the board or using dip switches. // Read the driver board's documentation to learn how to configure the driver // // all you need to do, to get started with this example, is fill in your wifi credentials in lines 26/27, then compile and upload to your ESP32. // In order to use the Web Interface of the server, you need to upload the contents of the "data" folder in this example to the SPIFFS of your ESP32 // // for a detailed manual on how to use this library please visit: https://github.com/pkerspe/ESP-StepperMotor-Server/blob/master/README.md // *********************************************************************** #include #include ESPStepperMotorServer *stepperMotorServer; const char *wifiName= ""; // enter the SSID of the wifi network to connect to const char *wifiSecret = ""; // enter the password of the the existing wifi network here void setup() { // start the serial interface with 115200 baud // IMPORTANT: the following line is important, since the server relies on the serial console for log output // Do not remove this line! (you can modify the baud rate to your needs though, but keep in mind, that slower baud rates might cause timing issues especially if you set the log level to DEBUG) Serial.begin(115200); // now create a new ESPStepperMotorServer instance (this must be done AFTER the Serial interface has been started) // In this example We create the server instance with all modules activated and log level set to INFO (which is the default, you can also use ESPServerLogLevel_DEBUG to set it to debug instead) stepperMotorServer = new ESPStepperMotorServer(ESPServerRestApiEnabled | ESPServerWebserverEnabled | ESPServerSerialEnabled, ESPServerLogLevel_INFO); // connect to an existing WiFi network. Make sure you set the vairables wifiName and wifiSecret to match you SSID and wifi pasword (see above before the setup function) stepperMotorServer->setWifiCredentials(wifiName, wifiSecret); stepperMotorServer->setWifiMode(ESPServerWifiModeClient); //start the server as a wifi client (DHCP client of an existing wifi network) // NOTE: if you want to start the server in a stand alone mode that opens a wifi access point, then comment out the above two lines and uncomment the following line // stepperMotorServer->setWifiMode(ESPServerWifiModeAccessPoint); // you can define the AP name and the password using the following two lines, otherwise the defaults will be used (Name: ESP-StepperMotor-Server, password: Aa123456) // stepperMotorServer->setAccessPointName(""); // stepperMotorServer->setAccessPointPassword(""); //start the server stepperMotorServer->start(); // the server will now connect to the wifi and start the webserver, rest API and serial command line interface. // check the serial console for more details like the URL of the WebInterface } void loop() { //put your code here } ================================================ FILE: examples/Example2_StepperMotorServer_with_hardcoded_config/Example2_StepperMotorServer_with_hardcoded_config.ino ================================================ // ***************************************************** // * Example how to configure via code * // * Paul Kerspe 31.5.2020 * // ***************************************************** // // This example shows how to configure the stepper server via code, to create a hardcoded configuation directly in the firmware. // this could be useful for example if you want to disable the Webinterface and REST API and solely control the steppers via the command line // and if you want to bundle a static configuration with the actual firmware to burn to multiple devices // this example will NOT start the webserver and REST API and will also not connect to a WiFi or open an access point. // If you intend to create a real server that can be controller via a User Interface or REST API see Example 1. // For this example you do not need SPIFFS and should not have a config.json uploaded to SPIFFS (since it would be loaded otherwise and possibly interfer with the coded config) // // This library requires that your stepper motor be connected to the ESP32 // using an external driver that has a "Step and Direction" interface. // // For all driver boards, it is VERY important that you set the motor // current before running the example. This is typically done by adjusting // a potentiometer on the board or using dip switches. // Read the driver board's documentation to learn how to configure the driver // // for a detailed manual on how to use this library please visit: https://github.com/pkerspe/ESP-StepperMotor-Server/blob/master/README.md // *********************************************************************** #include #include #include #include #include ESPStepperMotorServer *stepperMotorServer; ESPStepperMotorServer_StepperConfiguration *stepperConfiguration; #define STEP_PIN 16 #define DIRECTION_PIN 17 #define LIMIT_SWITCH_PIN 18 //this function gets called whenever the stepper reaches the target position / ends the current movement //it is registerd in the line "stepperConfiguration->getFlexyStepper()->registerTargetPositionReachedCallback(targetPositionReachedCallback);" void targetPositionReachedCallback(long position) { Serial.printf("Stepper reached target position %ld\n", position); } void setup() { Serial.begin(115200); // now create a new ESPStepperMotorServer instance (this must be done AFTER the Serial interface has been started) // In this example We create the server instance with only the serial command line interface enabled stepperMotorServer = new ESPStepperMotorServer(ESPServerSerialEnabled, ESPServerLogLevel_DEBUG); stepperMotorServer->setWifiMode(ESPServerWifiModeDisabled); //create a new configuration for a stepper stepperConfiguration = new ESPStepperMotorServer_StepperConfiguration(STEP_PIN, DIRECTION_PIN); stepperConfiguration->setDisplayName("X-Axis"); //configure the step size and microstepping setup of the drive/motor stepperConfiguration->setMicrostepsPerStep(1); stepperConfiguration->setStepsPerMM(100); stepperConfiguration->setStepsPerRev(200); //optional: if your stepper has a physical brake, configure the IO Pin of the brake and the behaviour // stepperConfiguration->setBrakeIoPin(20, SWITCHTYPE_STATE_ACTIVE_HIGH_BIT); //set the ESP Pin number where the brake control is connected to an confifgure as active high (brake is engaged when pin goes high) // stepperConfiguration->setBrakeEngageDelayMs(0); //instantly engage the brake after the stepper stops // stepperConfiguration->setBrakeReleaseDelayMs(-1); //-1 = never reease the brake unless stepper moves //OPTIONAL: register a callback handler to get informed whenever the stepper reaches the requested target position stepperConfiguration->getFlexyStepper()->registerTargetPositionReachedCallback(targetPositionReachedCallback); // now add the configuration to the server unsigned int stepperId = stepperMotorServer->addOrUpdateStepper(stepperConfiguration); //you can now also add switch and rotary encoder configurations to the server and link them to the steppers id if needed //here an example for a limit switch connected to the previously created stepper motor configuration (make sure the pin is not floating (use pull up or pull down resistor if needed)) ESPStepperMotorServer_PositionSwitch *positionSwitch = new ESPStepperMotorServer_PositionSwitch(LIMIT_SWITCH_PIN, stepperId, SWITCHTYPE_LIMITSWITCH_COMBINED_BEGIN_END_BIT, "Limit Switch"); stepperMotorServer->addOrUpdatePositionSwitch(positionSwitch); //start the server stepperMotorServer->start(); // check the serial console for more details and to send control signals } void loop() { //put your custom code here or use the following code to let the stepper motor go back and forth in an endless loop...how useful is that? :-) //to move the stepper motor we need to get the ESP FlexyStepper instance for this motor like this: ESP_FlexyStepper *flexyStepper = stepperConfiguration->getFlexyStepper(); flexyStepper->moveRelativeInSteps(100); delay(2000); flexyStepper->moveRelativeInSteps(-100); delay(2000); //for more details on the functions of ESP_FlexyStepper see here: https://github.com/pkerspe/ESP-FlexyStepper (chapter "function overview") } ================================================ FILE: examples/Example3_StepperMotorServer_with_static_IP_address/Example3_StepperMotorServer_with_static_IP_address.ino ================================================ // ***************************************************** // * Example how to configure static IP address * // * Paul Kerspe 9.10.2020 * // ***************************************************** // // This example shows how to configure the stepper server with a static IP address, gateway and subnet mask // you only need to modify lines 16 / 17 to configure your wifi SSID and password then compile and upload to your ESP32 // // for a detailed manual on how to use this library please visit: https://github.com/pkerspe/ESP-StepperMotor-Server/blob/master/README.md // *********************************************************************** #include #include ESPStepperMotorServer *stepperMotorServer; const char *wifiName = ""; // enter the SSID of the wifi network to connect to const char *wifiSecret = ""; // enter the password of the the existing wifi network here void setup() { // start the serial interface with 115200 baud // IMPORTANT: the following line is important, since the server relies on the serial console for log output // Do not remove this line! (you can modify the baud rate to your needs though, but keep in mind, that slower baud rates might cause timing issues especially if you set the log level to DEBUG) Serial.begin(115200); // now create a new ESPStepperMotorServer instance (this must be done AFTER the Serial interface has been started) // In this example We create the server instance with all modules activated and log level set to INFO (which is the default, you can also use ESPServerLogLevel_DEBUG to set it to debug instead) stepperMotorServer = new ESPStepperMotorServer(ESPServerRestApiEnabled | ESPServerWebserverEnabled | ESPServerSerialEnabled, ESPServerLogLevel_INFO); // connect to an existing WiFi network. Make sure you set the vairables wifiName and wifiSecret to match you SSID and wifi pasword (see above before the setup function) stepperMotorServer->setWifiCredentials(wifiName, wifiSecret); stepperMotorServer->setWifiMode(ESPServerWifiModeClient); //start the server as a wifi client (DHCP client of an existing wifi network) // here we set the static IP address: IPAddress staticIp(192, 168, 178, 49); IPAddress gatewayIp(192, 168, 178, 1); IPAddress subnetMask(255, 255, 255, 0); stepperMotorServer->setStaticIpAddress(staticIp, gatewayIp, subnetMask); //start the server stepperMotorServer->start(); // the server will now connect to the wifi and start the webserver, rest API and serial command line interface. // check the serial console for more details like the URL of the WebInterface } void loop() { //put your code here } ================================================ FILE: examples/Example4_StepperMotorServer_with_user_cli_command/Example4_StepperMotorServer_with_user_cli_command.ino ================================================ // ***************************************************** // * Example how to register a new CLI command * // * Tobias Ellinghaus 05.12.2023 * // ***************************************************** // // This examples show how to register a custom command for the CLI interface. // This could be useful if you want to control specific GPIO pins or trigger some other control logic. // This example is based on the hardcoded config example, so all remarks of that apply here, too. // // This library requires that your stepper motor be connected to the ESP32 // using an external driver that has a "Step and Direction" interface. // // For all driver boards, it is VERY important that you set the motor // current before running the example. This is typically done by adjusting // a potentiometer on the board or using dip switches. // Read the driver board's documentation to learn how to configure the driver // // for a detailed manual on how to use this library please visit: https://github.com/pkerspe/ESP-StepperMotor-Server/blob/master/README.md // *********************************************************************** #include #include #include #include #include ESPStepperMotorServer *stepperMotorServer; ESPStepperMotorServer_StepperConfiguration *stepperConfiguration; ESPStepperMotorServer_CLI *cli_handler; #define STEP_PIN 16 #define DIRECTION_PIN 17 #define ENABLE_PIN 18 void toggle_enable(char *cmd, char *args) { const int stepperid = cli_handler->getValidStepperIdFromArg(args); #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG ESPStepperMotorServer_Logger::logDebugf("%s called for stepper id %i\n", cmd, stepperid); #endif if (stepperid > -1) { char value[20]; cli_handler->getParameterValue(args, "v", value); if (value[0] != '\0') { #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG ESPStepperMotorServer_Logger::logDebugf("enabled called with v = %s\n", value); #endif const int on_off = (String(value).toInt()); digitalWrite(ENABLE_PIN, on_off ? HIGH : LOW); Serial.println(cmd); } else { Serial.println("error: missing required v parameter"); } } } void setup() { // configure our custom pin as an output and initialize it to LOW pinMode(ENABLE_PIN, OUTPUT); digitalWrite(ENABLE_PIN, LOW); Serial.begin(115200); // now create a new ESPStepperMotorServer instance (this must be done AFTER the Serial interface has been started) // In this example we create the server instance with only the serial command line interface enabled stepperMotorServer = new ESPStepperMotorServer(ESPServerSerialEnabled, ESPServerLogLevel_DEBUG); stepperMotorServer->setWifiMode(ESPServerWifiModeDisabled); // register a new CLI command to set the ENABLE pin cli_handler = stepperMotorServer->getCLIHandler(); cli_handler->registerNewUserCommand({String("enable"), String("e"), String("set the ENABLE signal of a specific stepper. requires the id of the stepper and also the value. E.g. e=0&v:1 to enable the ENABLE input on the stepper with id 0"), true}, &toggle_enable); //create a new configuration for a stepper stepperConfiguration = new ESPStepperMotorServer_StepperConfiguration(STEP_PIN, DIRECTION_PIN); stepperConfiguration->setDisplayName("X-Axis"); //configure the step size and microstepping setup of the drive/motor stepperConfiguration->setMicrostepsPerStep(1); stepperConfiguration->setStepsPerMM(100); stepperConfiguration->setStepsPerRev(200); // now add the configuration to the server unsigned int stepperId = stepperMotorServer->addOrUpdateStepper(stepperConfiguration); //start the server stepperMotorServer->start(); // check the serial console for more details and to send control signals } void loop() { //put your custom code here } ================================================ FILE: library.json ================================================ { "name": "ESP-StepperMotor-Server", "description": "A stepper motor control server for ESP32 modules that provides a Web UI, a REST API and a serial control interface. Support for limit switches and rotary encoders.", "keywords": "stepper,motor,http,websocket,webserver,rest,api,serial,controller,server,device-control,esp32", "authors": { "name": "Paul Kerspe", "maintainer": true }, "repository": { "type": "git", "url": "https://github.com/pkerspe/ESP-StepperMotor-Server.git" }, "version": "0.4.12", "license": "MIT", "frameworks": "arduino", "platforms": [ "espressif32" ], "dependencies": [{ "name": "ESP Async WebServer", "version": "1.2.3", "platforms": "espressif32" }, { "name": "ESP-FlexyStepper", "version": "^1.4.7", "platforms": "espressif32" }, { "name": "ArduinoJSON", "version": "6.21.2", "platforms": "arduino" }, { "name": "SPIFFS", "version": "2.0.0", "platforms": "arduino" } ], "examples": [ "[Ee]xamples/*/*.ino" ] } ================================================ FILE: library.properties ================================================ name=ESP-StepperMotor-Server version=0.4.12 author=Paul Kerspe maintainer=Paul Kerspe sentence=A stepper motor control server for ESP32 with Web UI, REST API and CLI paragraph=A stepper motor control server for ESP32 modules that provides a Web UI, a REST API and a serial control interface. Support for limit switches and rotary encoders. category=Device Control url=https://github.com/pkerspe/ESP-StepperMotor-Server architectures=esp32,espressif32 includes=ESPStepperMotorServer.h depends=ArduinoJSON (=6.21.2), ESP Async WebServer, ESP-FlexyStepper (>=1.4.7), SPIFFS ================================================ FILE: platformio.ini ================================================ ; PlatformIO Project Configuration File ; ; Build options: build flags, source filter ; Upload options: custom upload port, speed and extra flags ; Library options: dependencies, extra library storages ; Advanced options: extra scripting ; ; Please visit documentation for the other options and examples ; https://docs.platformio.org/page/projectconf.html [env:esp32devServer] platform = espressif32@6.12.0 build_flags = -fexceptions board = esp32dev framework = arduino lib_deps = ESP-FlexyStepper@^1.4.7 ESP32Async/ESPAsyncWebServer @ ^3.9.0 ArduinoJSON@6.21.2 littlefs board_build.partitions = default.csv monitor_speed = 115200 monitor_filters = esp32_exception_decoder, default ;monitor_port = /dev/cu.SLAB_USBtoUART ;upload_port = /dev/cu.SLAB_USBtoUART ================================================ FILE: src/ESPStepperMotorServer.cpp ================================================ // ********************************************************* // * * // * ESP8266 and ESP32 Stepper Motor Server * // * * // * Copyright (c) Paul Kerspe, 2019 * // * * // ********************************************************** // MIT License // // Copyright (c) 2019 Paul Kerspe // // Permission is hereby granted, free of charge, to any person obtaining a copy // of this software and associated documentation files (the "Software"), to deal // in the Software without restriction, including without limitation the rights // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell // copies of the Software, and to permit persons to whom the Software is furnished // to do so, subject to the following conditions: // // The above copyright notice and this permission notice shall be included in all // copies or substantial portions of the Software. // // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE // SOFTWARE. // // This library is used to start a server (Webserver, REST API or via serial port) to control and configure one or more stepper motors via a stepper driver module with step and direction input as well as optional homing switches // // Usage: // Near the top of the program, add: // include "ESPStepperMotorServer.h" // // e.g. to start the server and enable the web based user interface, the REST API and the serial server use: // ESPStepperMotorServer server(ESPServerRestApiEnabled|ESPServerWebserverEnabled|ESPServerSerialEnabled); // eg. to only start the web user interface and disable the rest API and serial server use: // ESPStepperMotorServer server(ESPServerWebserverEnabled); // // if the server is started with the ESPServerWebserverEnabled or ESPServerRestApiEnabled flag, you can specify a http port (default is port 80), for the server to listen for connections (e.g. port 80 in this example) if only starting in serial mode, you can ommit this step // server.setHttpPort(80); // // if you want the server to connect to an existing wifi network, you need to set the wifi ssid, username and password (replace "somessid", "someUser" and "somePwd" with the appropriate values for you network) // server.setWifiCredentials("someSsid","someUser","somePwd"); // OR if you do NOT want to connect to an EXISTING wifi network, then omit the setWifiCredentials call and instead configure the server to stat a separate Access Point by setting the Access Point name of your choice // NOTE: if you do not setWifiCredentials or setAccessPointName the server will start in access point mode with an ssid of "ESPStepperMotorServer" // server.setAccessPointName("myStepperServer"); // // after configuring the basic server, start it up as the last required step in the setup function: // server.start(); // #include // --------------------------------------------------------------------------------- // Setup functions // --------------------------------------------------------------------------------- ESPStepperMotorServer *ESPStepperMotorServer::anchor = NULL; // ESPStepperMotorServer::ESPStepperMotorServer(const ESPStepperMotorServer &espStepperMotorServer) // { // this->startSPIFFS(); // this->serverConfiguration = new ESPStepperMotorServer_Configuration(espStepperMotorServer.serverConfiguration->_configFilePath, this->isSPIFFSactive); // *this->serverConfiguration = *espStepperMotorServer.serverConfiguration; // #ifndef ESPStepperMotorServer_COMPILE_NO_WEB // if (espStepperMotorServer.webInterfaceHandler) // { // this->webInterfaceHandler = new ESPStepperMotorServer_WebInterface(this); // *this->webInterfaceHandler = *espStepperMotorServer.webInterfaceHandler; // } // if (espStepperMotorServer.restApiHandler) // { // this->restApiHandler = new ESPStepperMotorServer_RestAPI(this); // *this->restApiHandler = *espStepperMotorServer.restApiHandler; // } // #endif // if (espStepperMotorServer.cliHandler) // { // this->cliHandler = new ESPStepperMotorServer_CLI(this); // *this->cliHandler = *espStepperMotorServer.cliHandler; // } // if (espStepperMotorServer.motionControllerHandler) // { // this->motionControllerHandler = new ESPStepperMotorServer_MotionController(this); // *this->motionControllerHandler = *espStepperMotorServer.motionControllerHandler; // } // #ifndef ESPStepperMotorServer_COMPILE_NO_WEB // if (espStepperMotorServer.httpServer) // { // this->httpServer = new AsyncWebServer(this->serverConfiguration->serverPort); // *this->httpServer = *espStepperMotorServer.httpServer; // } // if (espStepperMotorServer.webSocketServer) // { // // check if needed, since in startWebserver it will be intialized again (~line 611) // this->webSocketServer = new AsyncWebSocket("/ws"); // *this->webSocketServer = *espStepperMotorServer.webSocketServer; // } // #endif // } ESPStepperMotorServer::~ESPStepperMotorServer() { delete this->serverConfiguration; #ifndef ESPStepperMotorServer_COMPILE_NO_WEB delete this->webInterfaceHandler; delete this->restApiHandler; #endif delete this->cliHandler; delete this->motionControllerHandler; } // // constructor for the stepper server class // ESPStepperMotorServer::ESPStepperMotorServer(byte serverMode, byte logLevel) { ESPStepperMotorServer_Logger::setLogLevel(logLevel); startSPIFFS(); // get config instance which tries to load config from SPIFFS by default this->serverConfiguration = new ESPStepperMotorServer_Configuration(this->defaultConfigurationFilename, this->isSPIFFSactive); this->enabledServices = serverMode; #ifndef ESPStepperMotorServer_COMPILE_NO_WEB if ((this->enabledServices & ESPServerWebserverEnabled) == ESPServerWebserverEnabled) { this->isWebserverEnabled = true; this->webInterfaceHandler = new ESPStepperMotorServer_WebInterface(this); } // rest api needs to be started either if web UI is enabled (which uses the REST API itself) or if REST API is enabled if ((this->enabledServices & ESPServerRestApiEnabled) == ESPServerRestApiEnabled || this->isWebserverEnabled) { this->isRestApiEnabled = true; this->restApiHandler = new ESPStepperMotorServer_RestAPI(this); } #endif if ((this->enabledServices & ESPServerSerialEnabled) == ESPServerSerialEnabled) { this->isCLIEnabled = true; this->cliHandler = new ESPStepperMotorServer_CLI(this); } this->motionControllerHandler = new ESPStepperMotorServer_MotionController(this); if (ESPStepperMotorServer::anchor != NULL) { ESPStepperMotorServer_Logger::logWarning("ESPStepperMotorServer must be used as a singleton, do not instanciate more than one server in your project"); } else { ESPStepperMotorServer::anchor = this; } } // --------------------------------------------------------------------------------- // general service control functions // --------------------------------------------------------------------------------- /** * ask the server to perform a reboot of the ESP. * this might be executed instantly or with a short delay depending on the current servers state */ void ESPStepperMotorServer::requestReboot(String rebootReason) { Serial.printf("Reboot scheduled, preparing shutdown. Reaon: %s\n", rebootReason.c_str()); this->_isRebootScheduled = true; } void ESPStepperMotorServer::start() { ESPStepperMotorServer_Logger::logInfof("Starting ESP-StepperMotor-Server (v. %s)\n", this->version); #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG this->printCompileSettings(); #endif if (this->serverConfiguration->wifiMode == ESPServerWifiModeAccessPoint) { this->startAccessPoint(); if (ESPStepperMotorServer_Logger::getLogLevel() >= ESPServerLogLevel_DEBUG) { this->printWifiStatus(); } } else if (this->serverConfiguration->wifiMode == ESPServerWifiModeClient) { this->connectToWifiNetwork(); if (ESPStepperMotorServer_Logger::getLogLevel() >= ESPServerLogLevel_DEBUG) { this->printWifiStatus(); } } else if (this->serverConfiguration->wifiMode == ESPServerWifiModeDisabled) { ESPStepperMotorServer_Logger::logInfo("WiFi mode is disabled, only serial control interface will be used for controls"); } #ifndef ESPStepperMotorServer_COMPILE_NO_WEB this->startWebserver(); #endif this->setupAllIOPins(); this->attachAllInterrupts(); if (this->isCLIEnabled) { this->cliHandler->start(); } this->motionControllerHandler->start(); this->isServerStarted = true; } void ESPStepperMotorServer::stop() { ESPStepperMotorServer_Logger::logInfo("Stopping ESP-StepperMotor-Server"); this->motionControllerHandler->stop(); this->detachAllInterrupts(); ESPStepperMotorServer_Logger::logInfo("detached interrupt handlers"); #ifndef ESPStepperMotorServer_COMPILE_NO_WEB if (isWebserverEnabled || isRestApiEnabled) { this->httpServer->end(); ESPStepperMotorServer_Logger::logInfo("stopped web server"); } #endif if (this->isCLIEnabled) { this->cliHandler->stop(); } this->isServerStarted = false; ESPStepperMotorServer_Logger::logInfo("ESP-StepperMotor-Server stopped"); } // --------------------------------------------------------------------------------- // Configuration Functions // --------------------------------------------------------------------------------- #ifndef ESPStepperMotorServer_COMPILE_NO_WEB void ESPStepperMotorServer::setHttpPort(int portNumber) { this->serverConfiguration->serverPort = portNumber; } #endif ESPStepperMotorServer_Configuration *ESPStepperMotorServer::getCurrentServerConfiguration() { return this->serverConfiguration; } int ESPStepperMotorServer::addOrUpdateRotaryEncoder(ESPStepperMotorServer_RotaryEncoder *encoder, int encoderIndex) { // add encoder to configuration if (encoderIndex > -1) { this->serverConfiguration->setRotaryEncoder(encoder, encoderIndex); } else { encoderIndex = (unsigned int)this->serverConfiguration->addRotaryEncoder(encoder); } this->setupRotaryEncoderIOPin(encoder); return encoderIndex; } /** * add or updated an existing stepper configuration * return the id of the stepper config (in case a new one has been added, or the given one in case of an update) * -1 is returned in case of an error (e.g. maximum number of configs reached for this entity) */ int ESPStepperMotorServer::addOrUpdateStepper(ESPStepperMotorServer_StepperConfiguration *stepper, int stepperIndex) { if (stepper->getStepIoPin() == ESPStepperMotorServer_StepperConfiguration::ESPServerStepperUnsetIoPinNumber || stepper->getDirectionIoPin() == ESPStepperMotorServer_StepperConfiguration::ESPServerStepperUnsetIoPinNumber) { ESPStepperMotorServer_Logger::logWarningf("Either the step IO pin (%i) or direction IO (%i) pin, or both, are not set correctly. Use a valid IO Pin value between 0 and the highest available IO Pin on your ESP\n", stepper->getStepIoPin(), stepper->getDirectionIoPin()); return -1; } // set IO Pins for stepper pinMode(stepper->getDirectionIoPin(), OUTPUT); digitalWrite(stepper->getDirectionIoPin(), LOW); pinMode(stepper->getStepIoPin(), OUTPUT); digitalWrite(stepper->getStepIoPin(), LOW); // add stepper to configuration or update existing one if (stepperIndex > -1) { this->serverConfiguration->setStepperConfiguration(stepper, stepperIndex); } else { stepperIndex = this->serverConfiguration->addStepperConfiguration(stepper); } return stepperIndex; } /** * remove the stepper configuration with the given index/id */ void ESPStepperMotorServer::removeStepper(byte id) { if (this->serverConfiguration->getStepperConfiguration(id)) { this->serverConfiguration->removeStepperConfiguration(id); } else { ESPStepperMotorServer_Logger::logWarningf("Stepper configuration index %i is invalid, no entry found or stepper IDs do not match, removeStepper() canceled\n", id); } } int ESPStepperMotorServer::addOrUpdatePositionSwitch(ESPStepperMotorServer_PositionSwitch *posSwitchToAdd, int switchIndex) { if (switchIndex > -1) { this->serverConfiguration->setSwitch(posSwitchToAdd, switchIndex); } else { switchIndex = (unsigned int)this->serverConfiguration->addSwitch(posSwitchToAdd); } // Setup IO Pin this->setupPositionSwitchIOPin(posSwitchToAdd); ESPStepperMotorServer_Logger::logInfof("Added switch '%s' for IO pin %i at configuration index %i\n", this->serverConfiguration->getSwitch(switchIndex)->getPositionName().c_str(), this->serverConfiguration->getSwitch(switchIndex)->getIoPinNumber(), switchIndex); return switchIndex; } void ESPStepperMotorServer::removePositionSwitch(int positionSwitchIndex) { ESPStepperMotorServer_PositionSwitch *posSwitch = this->serverConfiguration->getSwitch(positionSwitchIndex); if (posSwitch) { this->detachInterruptForPositionSwitch(posSwitch); #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG ESPStepperMotorServer_Logger::logDebugf("Removing position switch '%s' (id: %i) from configured switches\n", posSwitch->getPositionName().c_str(), positionSwitchIndex); #endif this->serverConfiguration->removeSwitch(positionSwitchIndex); } else { ESPStepperMotorServer_Logger::logWarning("Switch index %i is invalid, no switch configuration present at this index, removePositionSwitch() canceled\n", positionSwitchIndex); } } void ESPStepperMotorServer::removeRotaryEncoder(byte id) { if (this->serverConfiguration->getRotaryEncoder(id)) { this->serverConfiguration->removeRotaryEncoder(id); } else { ESPStepperMotorServer_Logger::logWarningf("rotary encoder index %i is invalid, no rotary encoder pointer present at this configuration index or rotary encoder IDs do not match, removeRotaryEncoder() canceled\n", id); } } // --------------------------------------------------------------------------------- // Status and Service Functions // --------------------------------------------------------------------------------- void ESPStepperMotorServer::getFormattedPositionSwitchStatusRegister(byte registerIndex, String &output) { String binary = String(this->buttonStatus[registerIndex], BIN); for (int i = 0; i < 8 - binary.length(); i++) { output += "0"; } output += binary; } void ESPStepperMotorServer::printPositionSwitchStatus() { // TODO reuse code in REST API const int docSize = 150 * ESPServerMaxSwitches; StaticJsonDocument doc; JsonObject root = doc.to(); JsonObject settings = root.createNestedObject("settings"); settings["positionSwitchCounterLimit"] = ESPServerMaxSwitches; settings["statusRegisterCounter"] = ESPServerSwitchStatusRegisterCount; JsonArray data = root.createNestedArray("switchStatusRegister"); for (byte i = 0; i < ESPServerSwitchStatusRegisterCount; i++) { JsonObject positionSwitchRegister = data.createNestedObject(); positionSwitchRegister["statusRegisterIndex"] = i; String binaryPadded = ""; this->getFormattedPositionSwitchStatusRegister(i, binaryPadded); positionSwitchRegister["status"] = binaryPadded; } JsonArray switches = root.createNestedArray("positionSwitches"); for (int i = 0; i < ESPServerMaxSwitches; i++) { if (this->serverConfiguration->getSwitch(i)) { JsonObject positionSwitch = switches.createNestedObject(); positionSwitch["id"] = i; positionSwitch["name"] = this->serverConfiguration->getSwitch(i)->getPositionName(); positionSwitch["ioPin"] = this->serverConfiguration->getSwitch(i)->getIoPinNumber(); positionSwitch["position"] = this->serverConfiguration->getSwitch(i)->getSwitchPosition(); positionSwitch["stepperId"] = this->serverConfiguration->getSwitch(i)->getStepperIndex(); positionSwitch["active"] = this->getPositionSwitchStatus(i); JsonObject positionSwichType = positionSwitch.createNestedObject("type"); if ((this->serverConfiguration->getSwitch(i)->getSwitchType() & ESPServerSwitchType_ActiveHigh) == ESPServerSwitchType_ActiveHigh) { positionSwichType["pinMode"] = "Active High"; } else { positionSwichType["pinMode"] = "Active Low"; } if ((this->serverConfiguration->getSwitch(i)->getSwitchType() & ESPServerSwitchType_HomingSwitchBegin) == ESPServerSwitchType_HomingSwitchBegin) { positionSwichType["switchType"] = "Homing switch (start-position)"; } else if ((this->serverConfiguration->getSwitch(i)->getSwitchType() & ESPServerSwitchType_HomingSwitchEnd) == ESPServerSwitchType_HomingSwitchEnd) { positionSwichType["switchType"] = "Homing switch (end-position)"; } else if ((this->serverConfiguration->getSwitch(i)->getSwitchType() & ESPServerSwitchType_GeneralPositionSwitch) == ESPServerSwitchType_GeneralPositionSwitch) { positionSwichType["switchType"] = "General position switch"; } else if ((this->serverConfiguration->getSwitch(i)->getSwitchType() & ESPServerSwitchType_EmergencyStopSwitch) == ESPServerSwitchType_EmergencyStopSwitch) { positionSwichType["switchType"] = "Emergency shut down switch"; } } } serializeJson(root, Serial); Serial.println(); } /** * checks if the configured position switch at the given configuration index is triggered (active) or not * This function takes the configured type ESPServerSwitchType_ActiveHigh or ESPServerSwitchType_ActiveLow into account when determining the current active state * e.g. if a switch is configured to be ESPServerSwitchType_ActiveLow the function will return 1 when the switch is triggered (low signal on IO pin). * For a switch that is configured ESPServerSwitchType_ActiveHigh on the other side, the function will return 0 when a low signal is on the IO pin, and 1 when a high signal is present */ byte ESPStepperMotorServer::getPositionSwitchStatus(int positionSwitchIndex) { ESPStepperMotorServer_PositionSwitch *posSwitch = this->serverConfiguration->getSwitch(positionSwitchIndex); if (posSwitch) { byte buttonState = digitalRead(posSwitch->getIoPinNumber()); if ((posSwitch->getSwitchType() & ESPServerSwitchType_ActiveHigh) == ESPServerSwitchType_ActiveHigh) { return (buttonState) ? 1 : 0; } else { return (buttonState) ? 0 : 1; } } return 0; } // --------------------------------------------------------------------------------- // CLI API functions // --------------------------------------------------------------------------------- ESPStepperMotorServer_CLI *ESPStepperMotorServer::getCLIHandler() const { return this->cliHandler; } // --------------------------------------------------------------------------------- // Web Server and REST API functions // --------------------------------------------------------------------------------- void ESPStepperMotorServer::startSPIFFS() { #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG ESPStepperMotorServer_Logger::logDebug("Checking LittleFS for existence and free space"); #endif bool littleFsBeginSuccess = LittleFS.begin(); if (!littleFsBeginSuccess) { ESPStepperMotorServer_Logger::logWarning("LittleFS cannot be mounted, trying to format LittleFS"); if (LittleFS.format()) { ESPStepperMotorServer_Logger::logInfo("LittleFS formatted, trying to mount again"); littleFsBeginSuccess = LittleFS.begin(); } else { ESPStepperMotorServer_Logger::logWarning("LittleFS formatting failed"); } } if (littleFsBeginSuccess) { this->isSPIFFSactive = true; #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG if (ESPStepperMotorServer_Logger::getLogLevel() >= ESPServerLogLevel_DEBUG) { ESPStepperMotorServer_Logger::logDebug("SPIFFS started"); printSPIFFSStats(); } #endif } else { this->isSPIFFSactive = false; if (this->isWebserverEnabled) { ESPStepperMotorServer_Logger::logWarning("Unable to activate LittleFS. Files for web interface cannot be loaded"); } } } bool ESPStepperMotorServer::isSPIFFSMounted() { return this->isSPIFFSactive; } void ESPStepperMotorServer::printSPIFFSStats() { if (this->isSPIFFSMounted()) { Serial.println("LittleFS stats:"); Serial.printf("Total bytes: %i\n", (int)LittleFS.totalBytes()); Serial.printf("bytes used: %i\n", (int)LittleFS.usedBytes()); Serial.printf("bytes free: %i\n", getSPIFFSFreeSpace()); } else { Serial.println("printSPIFFSStats: LittleFS not mounted"); } } void ESPStepperMotorServer::printSPIFFSRootFolderContents() { if (this->isSPIFFSMounted()) { File root = LittleFS.open("/"); if (!root) { ESPStepperMotorServer_Logger::logWarning("Failed to open root folder on SPIFFS for reading"); } if (root.isDirectory()) { ESPStepperMotorServer_Logger::logInfo("Listing files in root folder of SPIFFS:"); File file = root.openNextFile(); while (file) { ESPStepperMotorServer_Logger::logInfof("File: %s (%i) %ld\n", file.name(), file.size(), file.getLastWrite()); file = root.openNextFile(); } root.close(); } } else { ESPStepperMotorServer_Logger::logWarning("SPIFFS not mounted, printSPIFFSRootFolderContents() canceled"); } } int ESPStepperMotorServer::getSPIFFSFreeSpace() { if (this->isSPIFFSMounted()) { return ((int)LittleFS.totalBytes() - (int)LittleFS.usedBytes()); } else { return 0; } } #ifndef ESPStepperMotorServer_COMPILE_NO_WEB // TODO: test this part and implement usefull behavior void ESPStepperMotorServer::onWebSocketEvent(AsyncWebSocket *server, AsyncWebSocketClient *client, AwsEventType type, void *arg, uint8_t *data, size_t len) { if (type == WS_EVT_CONNECT) { ESPStepperMotorServer_Logger::logInfof("ws[%s][%u] connect\n", server->url(), client->id()); client->printf("Hello Client %u :)", client->id()); client->ping(); } else if (type == WS_EVT_DISCONNECT) { ESPStepperMotorServer_Logger::logInfof("ws[%s][%i] disconnect: %i\n", server->url(), client->id(), client->id()); } else if (type == WS_EVT_ERROR) { ESPStepperMotorServer_Logger::logWarningf("ws[%s][%u] error(%i): %s\n", server->url(), client->id(), *((uint16_t *)arg), (char *)data); } else if (type == WS_EVT_PONG) { ESPStepperMotorServer_Logger::logInfof("ws[%s][%i] pong[%i]: %s\n", server->url(), client->id(), (int)len, (len) ? (char *)data : ""); } else if (type == WS_EVT_DATA) { AwsFrameInfo *info = (AwsFrameInfo *)arg; String msg = ""; if (info->final && info->index == 0 && info->len == len) { // the whole message is in a single frame and we got all of it's data Serial.printf("ws[%s][%u] %s-message[%llu]: ", server->url(), client->id(), (info->opcode == WS_TEXT) ? "text" : "binary", info->len); if (info->opcode == WS_TEXT) { for (size_t i = 0; i < info->len; i++) { msg += (char)data[i]; } String commandFromClient = String((char *)data); if (commandFromClient.equals("status")) { client->text("Here is your status: OK"); } } else { char buff[10]; for (size_t i = 0; i < info->len; i++) { sprintf(buff, "%02x ", (uint8_t)data[i]); msg += buff; } } Serial.printf("%s\n", msg.c_str()); if (info->opcode == WS_TEXT) client->text("I got your text message"); else client->binary("I got your binary message"); } else { // message is comprised of multiple frames or the frame is split into multiple packets if (info->index == 0) { if (info->num == 0) Serial.printf("ws[%s][%u] %s-message start\n", server->url(), client->id(), (info->message_opcode == WS_TEXT) ? "text" : "binary"); Serial.printf("ws[%s][%u] frame[%u] start[%llu]\n", server->url(), client->id(), info->num, info->len); } Serial.printf("ws[%s][%u] frame[%u] %s[%llu - %llu]: ", server->url(), client->id(), info->num, (info->message_opcode == WS_TEXT) ? "text" : "binary", info->index, info->index + len); if (info->opcode == WS_TEXT) { for (size_t i = 0; i < info->len; i++) { msg += (char)data[i]; } } else { char buff[10]; for (size_t i = 0; i < info->len; i++) { sprintf(buff, "%02x ", (uint8_t)data[i]); msg += buff; } } Serial.printf("%s\n", msg.c_str()); if ((info->index + len) == info->len) { Serial.printf("ws[%s][%u] frame[%u] end[%llu]\n", server->url(), client->id(), info->num, info->len); if (info->final) { Serial.printf("ws[%s][%u] %s-message end\n", server->url(), client->id(), (info->message_opcode == WS_TEXT) ? "text" : "binary"); if (info->message_opcode == WS_TEXT) client->text("I got your text message"); else client->binary("I got your binary message"); } } } } } void ESPStepperMotorServer::startWebserver() { if (isWebserverEnabled || isRestApiEnabled) { printSPIFFSRootFolderContents(); httpServer = new AsyncWebServer(this->serverConfiguration->serverPort); ESPStepperMotorServer_Logger::logInfof("Starting webserver on port %i\n", this->serverConfiguration->serverPort); webSocketServer = new AsyncWebSocket("/ws"); webSocketServer->onEvent(std::bind(&ESPStepperMotorServer::onWebSocketEvent, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3, std::placeholders::_4, std::placeholders::_5, std::placeholders::_6)); httpServer->addHandler(webSocketServer); if (isWebserverEnabled) { this->webInterfaceHandler->registerWebInterfaceUrls(this->httpServer); } if (isRestApiEnabled) { this->restApiHandler->registerRestEndpoints(this->httpServer); } // SETUP CORS responses/headers DefaultHeaders::Instance().addHeader("Access-Control-Allow-Origin", "*"); DefaultHeaders::Instance().addHeader("Access-Control-Allow-Methods", "GET,POST,PUT,DELETE"); DefaultHeaders::Instance().addHeader("Access-Control-Allow-Headers", "Access-Control-Allow-Headers, Origin,Accept, X-Requested-With, Content-Type, Access-Control-Request-Method, Access-Control-Request-Headers"); httpServer->onNotFound([](AsyncWebServerRequest *request) { if (request->method() == HTTP_OPTIONS) { request->send(200); } else { request->send(404, "text/html", "

ESP-StepperMotor-Server

The requested file could not be found.
Either you have a typo in your URL or the web User Interface is not installed in the SPIFFS of your ESP. In the later case please Upload the User Interface files to SPIFFS before proceeding.

For more details refer to the installation manual"); } }); httpServer->begin(); ESPStepperMotorServer_Logger::logInfof("Webserver started, you can now open the user interface on http://%s:%i/\n", this->getIpAddress().c_str(), this->serverConfiguration->serverPort); } } void ESPStepperMotorServer::sendSocketMessageToAllClients(const char *message, size_t len) { // try sending message if clients are connected at all and if buffer is not already full if (this->webSocketServer->count() > 0 && this->webSocketServer->availableForWriteAll()) { this->webSocketServer->textAll(message, len); } } #endif String ESPStepperMotorServer::getIpAddress() { if (this->serverConfiguration->wifiMode == ESPServerWifiModeAccessPoint) { return WiFi.softAPIP().toString(); } else if (this->serverConfiguration->wifiMode == ESPServerWifiModeClient) { return WiFi.localIP().toString(); } else { return "not connected"; } } /** * get some server status information as a JSON formatted string. * Returns: version, wifi mode, ip address, spiffs information, enabled server modules */ void ESPStepperMotorServer::getServerStatusAsJsonString(String &statusString) { StaticJsonDocument<200> doc; JsonObject root = doc.to(); root["version"] = this->version; JsonObject wifiStatus = root.createNestedObject("wifi"); wifiStatus["mode"] = (this->serverConfiguration->wifiMode == ESPServerWifiModeAccessPoint) ? "ap" : "client"; wifiStatus["ip"] = (this->serverConfiguration->wifiMode == ESPServerWifiModeAccessPoint) ? WiFi.dnsIP().toString() : WiFi.localIP().toString(); JsonObject spiffsStatus = root.createNestedObject("littlefs"); if (this->isSPIFFSMounted()) { spiffsStatus["total_space"] = (int)LittleFS.totalBytes(); spiffsStatus["free_space"] = this->getSPIFFSFreeSpace(); } else { spiffsStatus["not_mounted"] = true; } JsonObject activeModules = root.createNestedObject("activeModules"); activeModules["serial_cli"] = (this->cliHandler != NULL); activeModules["rest_api"] = (this->isRestApiEnabled); activeModules["web_ui"] = (this->isWebserverEnabled); serializeJson(root, statusString); } // --------------------------------------------------------------------------------- // helper functions for stepper communication // --------------------------------------------------------------------------------- bool ESPStepperMotorServer::isIoPinUsed(int pinToCheck) { // TODO move to server configuration class // check stepper configurations for (int i = 0; i < ESPServerMaxSteppers; i++) { ESPStepperMotorServer_StepperConfiguration *stepperConfig = this->serverConfiguration->getStepperConfiguration(i); if (stepperConfig && (stepperConfig->getDirectionIoPin() == pinToCheck || stepperConfig->getStepIoPin() == pinToCheck || stepperConfig->getBrakeIoPin() == pinToCheck)) { return true; } } // check switch configurations for (int i = 0; i < ESPServerMaxSwitches; i++) { ESPStepperMotorServer_PositionSwitch *switchConfig = this->serverConfiguration->getSwitch(i); if (switchConfig && switchConfig->getIoPinNumber() == pinToCheck) { return true; } } return false; // check encoder configurations for (int i = 0; i < ESPServerMaxRotaryEncoders; i++) { ESPStepperMotorServer_RotaryEncoder *encoderConfig = this->serverConfiguration->getRotaryEncoder(i); if (encoderConfig && (encoderConfig->getPinAIOPin() == pinToCheck || encoderConfig->getPinBIOPin() == pinToCheck)) { return true; } } return false; } // --------------------------------------------------------------------------------- // WiFi functions // --------------------------------------------------------------------------------- void ESPStepperMotorServer::setAccessPointName(const char *accessPointSSID) { this->serverConfiguration->apName = accessPointSSID; } void ESPStepperMotorServer::setAccessPointPassword(const char *accessPointPassword) { this->serverConfiguration->apPassword = accessPointPassword; } void ESPStepperMotorServer::setWifiMode(byte wifiMode) { switch (wifiMode) { case ESPServerWifiModeAccessPoint: this->serverConfiguration->wifiMode = ESPServerWifiModeAccessPoint; break; case ESPServerWifiModeClient: this->serverConfiguration->wifiMode = ESPServerWifiModeClient; break; case ESPServerWifiModeDisabled: this->serverConfiguration->wifiMode = ESPServerWifiModeDisabled; break; default: ESPStepperMotorServer_Logger::logWarning("Invalid WiFi mode given in setWifiMode"); break; } } void ESPStepperMotorServer::printCompileSettings() { ESPStepperMotorServer_Logger::logDebugf("ESPStepperMotorServer compile settings (marcos):\nMax steppers: %i\nMax switches: %i\nMax encoders: %i\n", ESPServerMaxSteppers, ESPServerMaxSwitches, ESPServerMaxRotaryEncoders); } /** * print the wifi status (ssid, IP Address etc.) on the serial port */ void ESPStepperMotorServer::printWifiStatus() { ESPStepperMotorServer_Logger::logInfo("ESPStepperMotorServer WiFi details:"); if (this->serverConfiguration->staticIP != 0) { ESPStepperMotorServer_Logger::logInfof("Static IP address has been configured:\nIP: %s\nGateway: %s\nSubnet Mask:%s\n", this->serverConfiguration->staticIP.toString().c_str(), this->serverConfiguration->gatewayIP.toString().c_str(), this->serverConfiguration->subnetMask.toString().c_str()); } if (this->serverConfiguration->wifiMode == ESPServerWifiModeClient) { ESPStepperMotorServer_Logger::logInfo("WiFi status: server acts as wifi client in existing network with DHCP"); ESPStepperMotorServer_Logger::logInfof("SSID: %s\n", this->getCurrentServerConfiguration()->wifiSsid); ESPStepperMotorServer_Logger::logInfof("IP address: %s\n", WiFi.localIP().toString().c_str()); ESPStepperMotorServer_Logger::logInfof("Strength: %i dBm\n", WiFi.RSSI()); // Received Signal Strength Indicator } else if (this->serverConfiguration->wifiMode == ESPServerWifiModeAccessPoint) { ESPStepperMotorServer_Logger::logInfo("WiFi status: access point started"); ESPStepperMotorServer_Logger::logInfof("SSID: %s\n", this->serverConfiguration->apName); ESPStepperMotorServer_Logger::logInfof("IP Address: %s\n", WiFi.softAPIP().toString().c_str()); } else { ESPStepperMotorServer_Logger::logInfo("WiFi is disabled"); } } void ESPStepperMotorServer::setWifiSSID(const char *ssid) { this->getCurrentServerConfiguration()->wifiSsid = ssid; } void ESPStepperMotorServer::setWifiPassword(const char *pwd) { this->getCurrentServerConfiguration()->wifiPassword = pwd; } void ESPStepperMotorServer::setWifiCredentials(const char *ssid, const char *pwd) { this->setWifiSSID(ssid); this->setWifiPassword(pwd); } void ESPStepperMotorServer::setStaticIpAddress(IPAddress staticIP, IPAddress gatewayIP, IPAddress subnetMask, IPAddress dns1, IPAddress dns2) { this->getCurrentServerConfiguration()->staticIP = staticIP; this->getCurrentServerConfiguration()->gatewayIP = gatewayIP; this->getCurrentServerConfiguration()->subnetMask = subnetMask; this->getCurrentServerConfiguration()->dns1IP = dns1; this->getCurrentServerConfiguration()->dns2IP = dns2; } void ESPStepperMotorServer::startAccessPoint() { WiFi.softAP(this->serverConfiguration->apName, this->serverConfiguration->apPassword); ESPStepperMotorServer_Logger::logInfof("Started Access Point with name %s and IP %s\n", this->serverConfiguration->apName, WiFi.softAPIP().toString().c_str()); } void ESPStepperMotorServer::connectToWifiNetwork() { if (WiFi.status() == WL_CONNECTED) { ESPStepperMotorServer_Logger::logInfo("Module is already conencted to WiFi network. Will skip WiFi connection procedure"); return; } if (this->serverConfiguration->staticIP != 0) { ESPStepperMotorServer_Logger::logInfof("Static IP address has been configured, will use %s\n", this->serverConfiguration->staticIP.toString().c_str()); WiFi.config(this->serverConfiguration->staticIP, this->serverConfiguration->gatewayIP, this->serverConfiguration->subnetMask, this->serverConfiguration->dns1IP, this->serverConfiguration->dns2IP); } if ((this->getCurrentServerConfiguration()->wifiSsid != NULL) && (this->getCurrentServerConfiguration()->wifiSsid[0] == '\0')) { ESPStepperMotorServer_Logger::logWarning("No SSID has been configured to connect to. Connection to existing WiFi network aborted"); return; } bool noWifiPwd = (!this->getCurrentServerConfiguration()->wifiPassword || this->getCurrentServerConfiguration()->wifiPassword[0] == '\0'); ESPStepperMotorServer_Logger::logInfof("Trying to connect to WiFi with SSID '%s' %s...", this->getCurrentServerConfiguration()->wifiSsid, (noWifiPwd ? "without password" : "")); if (noWifiPwd) { WiFi.begin(this->getCurrentServerConfiguration()->wifiSsid); } else { WiFi.begin(this->getCurrentServerConfiguration()->wifiSsid, this->getCurrentServerConfiguration()->wifiPassword); } int retryIntervalMs = 500; int timeoutCounter = this->wifiClientConnectionTimeoutSeconds * (1000 / retryIntervalMs); while (WiFi.status() != WL_CONNECTED && timeoutCounter > 0) { delay(retryIntervalMs); ESPStepperMotorServer_Logger::logInfo(".", false, true); if (timeoutCounter == (this->wifiClientConnectionTimeoutSeconds * 2 - 3)) { WiFi.reconnect(); } timeoutCounter--; } ESPStepperMotorServer_Logger::logInfo("\n", false, true); if (timeoutCounter > 0) { ESPStepperMotorServer_Logger::logInfof("Connected to network with IP address %s\n", WiFi.localIP().toString().c_str()); } else { ESPStepperMotorServer_Logger::logWarningf("Connection to WiFi network with SSID '%s' failed with timeout\n", this->getCurrentServerConfiguration()->wifiSsid); #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG ESPStepperMotorServer_Logger::logDebugf("Connection timeout is set to %i seconds\n", this->wifiClientConnectionTimeoutSeconds); #endif ESPStepperMotorServer_Logger::logWarningf("starting server in access point mode with SSID '%s' and password '%s' as fallback\n", this->serverConfiguration->apName, this->serverConfiguration->apPassword); this->setWifiMode(ESPServerWifiModeAccessPoint); this->startAccessPoint(); } } void ESPStepperMotorServer::scanWifiNetworks() { int numberOfNetworks = WiFi.scanNetworks(); Serial.print("Number of networks found:"); Serial.println(numberOfNetworks); for (int i = 0; i < numberOfNetworks; i++) { Serial.print("SSID: "); Serial.println(WiFi.SSID(i)); Serial.print("Signal strength: "); Serial.println(WiFi.RSSI(i)); } } // --------------------------------------------------------------------------------- // IO Setup and Interrupt functions // --------------------------------------------------------------------------------- /** * setup the IO Pin to INPUT mode */ void ESPStepperMotorServer::setupPositionSwitchIOPin(ESPStepperMotorServer_PositionSwitch *posSwitch) { if (posSwitch) { if (posSwitch->isActiveHigh()) { #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG ESPStepperMotorServer_Logger::logDebugf("Setting up IO pin %i as input for active high switch '%s' (%i)\n", posSwitch->getIoPinNumber(), posSwitch->getPositionName().c_str(), posSwitch->getId()); #endif pinMode(posSwitch->getIoPinNumber(), INPUT); } else { if (posSwitch->getIoPinNumber() == 34 || posSwitch->getIoPinNumber() == 35 || posSwitch->getIoPinNumber() == 36 || posSwitch->getIoPinNumber() == 39) { ESPStepperMotorServer_Logger::logWarningf("The configured IO pin %i cannot be used for active low switches unless an external pull up resistor is in place. The ESP does not provide internal pullups on this IO pin. Make sure you have a pull up resistor in place for the switch %s (%i)\n", posSwitch->getIoPinNumber(), posSwitch->getPositionName(), posSwitch->getId()); } #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG ESPStepperMotorServer_Logger::logDebugf("Setting up IO pin %i as input with pullup for active low switch '%s' (%i)\n", posSwitch->getIoPinNumber(), posSwitch->getPositionName().c_str(), posSwitch->getId()); #endif pinMode(posSwitch->getIoPinNumber(), INPUT_PULLUP); } } } void ESPStepperMotorServer::setupRotaryEncoderIOPin(ESPStepperMotorServer_RotaryEncoder *rotaryEncoder) { // set Pins for encoder #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG ESPStepperMotorServer_Logger::logDebugf("Setting up IO pin %i as Pin A input with internal pullup for rotary encoder '%s' (%i)\n", rotaryEncoder->getPinAIOPin(), rotaryEncoder->getDisplayName().c_str(), rotaryEncoder->getId()); #endif pinMode(rotaryEncoder->getPinAIOPin(), INPUT_PULLUP); #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG ESPStepperMotorServer_Logger::logDebugf("Setting up IO pin %i as Pin B input with internal pullup for rotary encoder '%s' (%i)\n", rotaryEncoder->getPinBIOPin(), rotaryEncoder->getDisplayName().c_str(), rotaryEncoder->getId()); #endif pinMode(rotaryEncoder->getPinBIOPin(), INPUT_PULLUP); } /** * setup the IO Pins for all configured switches and encoders */ void ESPStepperMotorServer::setupAllIOPins() { // setup IO pins for all switches for (byte switchId = 0; switchId < ESPServerMaxSwitches; switchId++) { ESPStepperMotorServer_PositionSwitch *switchConfig = this->serverConfiguration->getSwitch(switchId); if (switchConfig) { this->setupPositionSwitchIOPin(switchConfig); } } // Setup IO pins for all encoders for (byte encoderId = 0; encoderId < ESPServerMaxRotaryEncoders; encoderId++) { ESPStepperMotorServer_RotaryEncoder *encoderConfig = this->serverConfiguration->getRotaryEncoder(encoderId); if (encoderConfig) { this->setupRotaryEncoderIOPin(encoderConfig); } } this->updateSwitchStatusRegister(); } /** * Register ISR according to switch type (active high or active low) for all configured position switches */ void ESPStepperMotorServer::attachAllInterrupts() { for (int i = 0; i < ESPServerMaxSwitches; i++) { ESPStepperMotorServer_PositionSwitch *posSwitch = this->serverConfiguration->getSwitch(i); if (posSwitch) { char irqNum = digitalPinToInterrupt(posSwitch->getIoPinNumber()); if (irqNum == NOT_AN_INTERRUPT) { ESPStepperMotorServer_Logger::logWarningf("Failed to determine IRQ# for given IO pin %i, thus setting up of interrupt for the position switch '%s' failed\n", posSwitch->getIoPinNumber(), posSwitch->getPositionName().c_str()); } else { _BV(irqNum); // clear potentially pending interrupts // register emergency stop switches if (posSwitch->isEmergencySwitch()) { #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG ESPStepperMotorServer_Logger::logDebugf("Attaching interrupt service routine for emergency stop switch '%s' on IO pin %i\n", posSwitch->getPositionName().c_str(), posSwitch->getIoPinNumber()); #endif attachInterrupt(irqNum, staticEmergencySwitchISR, CHANGE); } // register limit switches else if (posSwitch->isLimitSwitch()) { #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG ESPStepperMotorServer_Logger::logDebugf("Attaching interrupt service routine for limit switch '%s' on IO pin %i\n", posSwitch->getPositionName().c_str(), posSwitch->getIoPinNumber()); #endif if (posSwitch->isTypeBitSet(SWITCHTYPE_LIMITSWITCH_POS_END_BIT)) { attachInterrupt(irqNum, staticLimitSwitchISR_POS_END, CHANGE); } else if (posSwitch->isTypeBitSet(SWITCHTYPE_LIMITSWITCH_POS_BEGIN_BIT)) { attachInterrupt(irqNum, staticLimitSwitchISR_POS_BEGIN, CHANGE); } else if (posSwitch->isTypeBitSet(SWITCHTYPE_LIMITSWITCH_COMBINED_BEGIN_END_BIT)) { attachInterrupt(irqNum, staticLimitSwitchISR_COMBINED, CHANGE); } } // register general position switches & others else { #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG ESPStepperMotorServer_Logger::logDebugf("Attaching interrupt service routine for general position switch '%s' on IO pin %i\n", posSwitch->getPositionName().c_str(), posSwitch->getIoPinNumber()); #endif attachInterrupt(irqNum, staticPositionSwitchISR, CHANGE); } } } } for (int i = 0; i < ESPServerMaxRotaryEncoders; i++) { ESPStepperMotorServer_RotaryEncoder *rotaryEncoder = this->serverConfiguration->getRotaryEncoder(i); if (rotaryEncoder != NULL) { // we do a loop here to save some program memory, could also externalize code block in another function const unsigned char pins[2] = {rotaryEncoder->getPinAIOPin(), rotaryEncoder->getPinBIOPin()}; for (int i = 0; i < 2; i++) { char irqNum = digitalPinToInterrupt(pins[i]); if (irqNum == NOT_AN_INTERRUPT) { ESPStepperMotorServer_Logger::logWarningf("Failed to determine IRQ# for given IO pin %i, thus setting up of interrupt for the rotary encoder failed for pin %s\n", pins[i], rotaryEncoder->getDisplayName().c_str()); } _BV(irqNum); // clear potentially pending interrupts attachInterrupt(irqNum, staticRotaryEncoderISR, CHANGE); } } } } void ESPStepperMotorServer::detachInterruptForPositionSwitch(ESPStepperMotorServer_PositionSwitch *posSwitch) { #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG ESPStepperMotorServer_Logger::logDebugf("detaching interrupt for position switch %s on IO Pin %i\n", posSwitch->getPositionName().c_str(), posSwitch->getIoPinNumber()); #endif detachInterrupt(digitalPinToInterrupt(posSwitch->getIoPinNumber())); } void ESPStepperMotorServer::detachInterruptForRotaryEncoder(ESPStepperMotorServer_RotaryEncoder *rotaryEncoder) { #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG ESPStepperMotorServer_Logger::logDebugf("detaching interrupts for rotary encoder %s on IO Pins %i and %i\n", rotaryEncoder->getDisplayName().c_str(), rotaryEncoder->getPinAIOPin(), rotaryEncoder->getPinBIOPin()); #endif // Pin A of rotary encoder if (digitalPinToInterrupt(rotaryEncoder->getPinAIOPin()) != NOT_AN_INTERRUPT) { detachInterrupt(digitalPinToInterrupt(rotaryEncoder->getPinAIOPin())); } // Pin B of rotary encoder if (digitalPinToInterrupt(rotaryEncoder->getPinBIOPin()) != NOT_AN_INTERRUPT) { detachInterrupt(digitalPinToInterrupt(rotaryEncoder->getPinBIOPin())); } } /** * clear/disable all interrupts for position switches **/ void ESPStepperMotorServer::detachAllInterrupts() { for (int i = 0; i < ESPServerMaxSwitches; i++) { ESPStepperMotorServer_PositionSwitch *posSwitch = this->serverConfiguration->getSwitch(i); if (posSwitch) { this->detachInterruptForPositionSwitch(posSwitch); } } for (int i = 0; i < ESPServerMaxRotaryEncoders; i++) { ESPStepperMotorServer_RotaryEncoder *rotaryEncoder = this->serverConfiguration->getRotaryEncoder(i); if (rotaryEncoder != NULL) { this->detachInterruptForRotaryEncoder(rotaryEncoder); } } } /** * Trigger an emergency stop. Can be called with optional stepper ID to only trigger emergency stop for a specific stepper. * If called without the parameter, all configured steppers will be stopped ************************************************************************************************************************** * IMPORTANT NOTE: This function can be called manually, but will also be called from the ISR of the Emegerncy switches, * * so it should be kept as short as possible and not use the CoProcessor (E.g. for floating point arithmetic operations) * ************************************************************************************************************************** */ void ESPStepperMotorServer::performEmergencyStop(int stepperId) { this->emergencySwitchIsActive = true; // only perform emergency stop for one stepper if (stepperId > -1 && stepperId != 255) { ESPStepperMotorServer_StepperConfiguration *stepper = this->serverConfiguration->getStepperConfiguration(stepperId); if (stepper) { stepper->getFlexyStepper()->emergencyStop(); } } else { // perform complete stop on all steppers ESP_FlexyStepper **configuredFlexySteppers = this->serverConfiguration->getConfiguredFlexySteppers(); for (byte i = 0; i < ESPServerMaxSteppers; i++) { if (configuredFlexySteppers[i]) { configuredFlexySteppers[i]->emergencyStop(); } else { break; } } } } void ESPStepperMotorServer::revokeEmergencyStop() { this->emergencySwitchIsActive = false; } /** * Update the switch status register by reading all configured IO pins. * Returns the pin Number of the last IO pin where a change has been detected for since last the update of the register. * -1 is returned if not change could be detected / no switch is configured */ signed char ESPStepperMotorServer::updateSwitchStatusRegister() { byte registerIndex = 0; signed char changedSwitchIndex = -1; signed char *allSwitchIoPins = this->serverConfiguration->allSwitchIoPins; volatile byte *buttonStatus = this->buttonStatus; // iterate over all configured position switch IO pins and read state and write to status registers for (int switchIndex = 0; switchIndex < ESPServerMaxSwitches; switchIndex++) { signed char ioPin = allSwitchIoPins[switchIndex]; if (ioPin > -1) { if (switchIndex > 7) // write to next register if needed { registerIndex = (byte)(ceil)((switchIndex + 1) / 8); } byte previousPinState = bitRead(buttonStatus[registerIndex], switchIndex % 8); byte currentPinState = digitalRead(ioPin); if (currentPinState == HIGH && previousPinState == LOW) { #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG if (ESPStepperMotorServer_Logger::isDebugEnabled()) ESPStepperMotorServer_Logger::logDebugf("Setting bit %i to high in register for switch %i with io pin %i\n", (switchIndex % 8), switchIndex, ioPin); #endif bitSet(this->buttonStatus[registerIndex], switchIndex % 8); changedSwitchIndex = switchIndex; } else if (currentPinState == LOW && previousPinState == HIGH) { #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG if (ESPStepperMotorServer_Logger::isDebugEnabled()) ESPStepperMotorServer_Logger::logDebugf("Setting bit %i to low in register for switch %i with io pin %i\n", (switchIndex % 8), switchIndex, ioPin); #endif bitClear(buttonStatus[registerIndex], switchIndex % 8); changedSwitchIndex = switchIndex; } } } return changedSwitchIndex; } void IRAM_ATTR ESPStepperMotorServer::staticPositionSwitchISR() { anchor->internalSwitchISR(SWITCHTYPE_POSITION_SWITCH_BIT); } void IRAM_ATTR ESPStepperMotorServer::staticEmergencySwitchISR() { anchor->internalEmergencySwitchISR(); } void IRAM_ATTR ESPStepperMotorServer::staticLimitSwitchISR_POS_BEGIN() { anchor->internalSwitchISR(SWITCHTYPE_LIMITSWITCH_POS_BEGIN_BIT); } void IRAM_ATTR ESPStepperMotorServer::staticLimitSwitchISR_POS_END() { anchor->internalSwitchISR(SWITCHTYPE_LIMITSWITCH_POS_END_BIT); } void IRAM_ATTR ESPStepperMotorServer::staticLimitSwitchISR_COMBINED() { anchor->internalSwitchISR(SWITCHTYPE_LIMITSWITCH_COMBINED_BEGIN_END_BIT); } void IRAM_ATTR ESPStepperMotorServer::staticRotaryEncoderISR() { anchor->internalRotaryEncoderISR(); } void IRAM_ATTR ESPStepperMotorServer::internalEmergencySwitchISR() { ESPStepperMotorServer_PositionSwitch *switchConfig; for (byte i = 0; i < ESPServerMaxSwitches; i++) { switchConfig = this->serverConfiguration->configuredEmergencySwitches[i]; if (switchConfig != NULL) { byte registerIndex = 0; byte switchId = switchConfig->getId(); if (switchId > 7) // write to next register if needed registerIndex = (byte)(ceil)((switchId + 1) / 8); byte pinState = digitalRead(switchConfig->getIoPinNumber()); if (pinState) bitSet(this->buttonStatus[registerIndex], (switchId % 8)); else bitClear(this->buttonStatus[registerIndex], (switchId % 8)); bool isActiveHigh = switchConfig->isActiveHigh(); bool switchIsActive = ((pinState && isActiveHigh) || (!pinState && !isActiveHigh)); if (switchIsActive) this->performEmergencyStop(switchConfig->getStepperIndex()); else // TODO: this might cause issues with multiple Emergency Switches connected since it will revoke the global flag // so if only the first switch is triggered, the second one will be checked in this loop and revoke the flag this->emergencySwitchIsActive = false; } else break; } } /** * ISR for general switch interrupts * NOTE: this ISR is not called for emergency switches (since fastest possible processing time is required and we need to avoid all these loops). * Look at internalEmergencySwitchISR() instead for emergency switch handling */ void IRAM_ATTR ESPStepperMotorServer::internalSwitchISR(byte switchType) { signed char changedStausSwitchId = this->updateSwitchStatusRegister(); if (changedStausSwitchId > -1 && (switchType == SWITCHTYPE_LIMITSWITCH_POS_BEGIN_BIT || switchType == SWITCHTYPE_LIMITSWITCH_POS_END_BIT || switchType == SWITCHTYPE_LIMITSWITCH_COMBINED_BEGIN_END_BIT)) { ESPStepperMotorServer_Configuration *configuration = this->serverConfiguration; ESPStepperMotorServer_PositionSwitch *switchConfig = configuration->allConfiguredSwitches[changedStausSwitchId]; if (switchConfig) { bool isActiveHigh = switchConfig->_switchType & (1 << (SWITCHTYPE_STATE_ACTIVE_HIGH_BIT - 1)); // we do not use the helper function isActiveHigh due to performance reasons bool inputState = digitalRead(switchConfig->_ioPinNumber); ESPStepperMotorServer_StepperConfiguration *stepper = configuration->getStepperConfiguration(switchConfig->_stepperIndex); if (stepper) { if ((inputState && isActiveHigh) || (!inputState && !isActiveHigh)) { switch (switchType) { case SWITCHTYPE_LIMITSWITCH_POS_BEGIN_BIT: stepper->_flexyStepper->setLimitSwitchActive(ESP_FlexyStepper::LIMIT_SWITCH_BEGIN); break; case SWITCHTYPE_LIMITSWITCH_POS_END_BIT: stepper->_flexyStepper->setLimitSwitchActive(ESP_FlexyStepper::LIMIT_SWITCH_END); break; case SWITCHTYPE_LIMITSWITCH_COMBINED_BEGIN_END_BIT: stepper->_flexyStepper->setLimitSwitchActive(ESP_FlexyStepper::LIMIT_SWITCH_COMBINED_BEGIN_AND_END); break; } } else { stepper->_flexyStepper->clearLimitSwitchActive(); } } } else { ESPStepperMotorServer_Logger::logWarningf("A IO Pin change has been detected for switch id %i which is not a limit switch, but the ISR was triggered for a switch of type limit switch. It is possible that a limit switch status change has not been detected properly\n", changedStausSwitchId); } } } /** * the ISR to handle rotary encoder related pin interrupts and trigger the stepper position change */ void IRAM_ATTR ESPStepperMotorServer::internalRotaryEncoderISR() { ESPStepperMotorServer_Configuration *configuration = this->serverConfiguration; for (int i = 0; i < ESPServerMaxRotaryEncoders; i++) { ESPStepperMotorServer_RotaryEncoder *rotaryEncoder = configuration->configuredRotaryEncoders[i]; if (rotaryEncoder != NULL) { unsigned char result = rotaryEncoder->process(); ESPStepperMotorServer_StepperConfiguration *stepperConfig = configuration->configuredSteppers[rotaryEncoder->_stepperIndex]; if (stepperConfig) { if (result == DIR_CW) { stepperConfig->_flexyStepper->setTargetPositionRelativeInSteps(1 * rotaryEncoder->_stepMultiplier); } else if (result == DIR_CCW) { signed long newPosition = -1L * rotaryEncoder->_stepMultiplier; stepperConfig->_flexyStepper->setTargetPositionRelativeInSteps(newPosition); } } else { ESPStepperMotorServer_Logger::logWarningf("Invalid stepper config id %i for rotary enc. (id=%i)\n", rotaryEncoder->_stepperIndex, i); } } } } // ----------------- delegator functions to ease API usage ------------------------- void ESPStepperMotorServer::setLogLevel(byte logLevel) { ESPStepperMotorServer_Logger::setLogLevel(logLevel); } // -------------------------------------- End -------------------------------------- ================================================ FILE: src/ESPStepperMotorServer.h ================================================ // ****************************************************************** // * * // * Header file for ESPStepperMotorServer.cpp * // * * // * Copyright (c) Paul Kerspe, 2019 * // * * // ****************************************************************** // this project is not supposed to replace a controller of a CNC machine but more of a general approach on working with stepper motors // for a good Arduino/ESP base Gerber compatible controller Project see: // https://github.com/gnea/grbl // and for ESP32: https://github.com/bdring/Grbl_Esp32 // currently no G-Code (http://linuxcnc.org/docs/html/gcode.html) parser is implemented, yet it might be part of a future release // other usefull informaion when connecting your ESP32 board to your driver boards and you are not sure which pins to use: https://randomnerdtutorials.com/esp32-pinout-reference-gpios/ // MIT License // // Copyright (c) 2019 Paul Kerspe // // Permission is hereby granted, free of charge, to any person obtaining a copy // of this software and associated documentation files (the "Software"), to deal // in the Software without restriction, including without limitation the rights // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell // copies of the Software, and to permit persons to whom the Software is furnished // to do so, subject to the following conditions: // // The above copyright notice and this permission notice shall be included in all // copies or substantial portions of the Software. // // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE // SOFTWARE. #ifndef ESPStepperMotorServer_h #define ESPStepperMotorServer_h #define ESPServerMaxSwitches 10 #define ESPServerSwitchStatusRegisterCount 2 //NOTE: this value must be chosen according to the value of ESPServerMaxSwitches: val = ceil(ESPServerMaxSwitches / 8) #define ESPServerMaxSteppers 10 #define ESPServerMaxRotaryEncoders 5 #define ESPStepperMotorServer_SwitchDisplayName_MaxLength 20 #include #include #include #include #ifndef ESPStepperMotorServer_COMPILE_NO_WEB #include #include #endif #include #include #include #include #include #include #include #include #ifndef ESPStepperMotorServer_COMPILE_NO_WEB #include #endif #define ESPServerWifiModeDisabled 0 #define ESPServerWifiModeAccessPoint 1 #define ESPServerWifiModeClient 2 #define ESPServerRestApiEnabled 2 #define ESPServerWebserverEnabled 4 #define ESPServerSerialEnabled 8 #define ESPServerSwitchType_ActiveHigh 1 #define ESPServerSwitchType_ActiveLow 2 #define ESPServerSwitchType_HomingSwitchBegin 4 #define ESPServerSwitchType_HomingSwitchEnd 8 #define ESPServerSwitchType_GeneralPositionSwitch 16 #define ESPServerSwitchType_EmergencyStopSwitch 32 #define ESPStepperHighestAllowedIoPin 50 //just forward declare class here for compiler, since we have a circular dependency (due to bad api design :-)) class ESPStepperMotorServer_CLI; class ESPStepperMotorServer_RestAPI; class ESPStepperMotorServer_Configuration; class ESPStepperMotorServer_MotionController; class ESPStepperMotorServer_MacroAction; #ifndef ESPStepperMotorServer_COMPILE_NO_WEB class ESPStepperMotorServer_WebInterface; class ESPStepperMotorServer_RestAPI; #endif // // the ESPStepperMotorServer class // TODO: remove all wifi stuff if not needed using: #if defined(ESPServerWifiModeClient) || defined(ESPServerWifiModeAccessPoint) class ESPStepperMotorServer { friend class ESPStepperMotorServer_MotionController; public: ESPStepperMotorServer(byte serverMode, byte logLevel = ESPServerLogLevel_INFO); ESPStepperMotorServer(const ESPStepperMotorServer &espStepperMotorServer); ~ESPStepperMotorServer(); #ifndef ESPStepperMotorServer_COMPILE_NO_WEB void setHttpPort(int portNumber); void onWebSocketEvent(AsyncWebSocket *server, AsyncWebSocketClient *client, AwsEventType type, void *arg, uint8_t *data, size_t len); void sendSocketMessageToAllClients(const char *message, size_t len); #endif void setAccessPointName(const char *accessPointSSID); void setAccessPointPassword(const char *accessPointPassword); void setWifiCredentials(const char *ssid, const char *pwd); void setWifiSSID(const char *ssid); void setWifiPassword(const char *pwd); void setWifiMode(byte wifiMode); void setStaticIpAddress(IPAddress staticIP, IPAddress gatewayIP, IPAddress subnetMask, IPAddress dns1 = (uint32_t) 0x00000000, IPAddress dns2 = (uint32_t) 0x00000000); void printWifiStatus(); void printCompileSettings(); int addOrUpdateStepper(ESPStepperMotorServer_StepperConfiguration *stepper, int stepperIndex = -1); int addOrUpdatePositionSwitch(ESPStepperMotorServer_PositionSwitch *posSwitchToAdd, int switchIndex = -1); int addOrUpdateRotaryEncoder(ESPStepperMotorServer_RotaryEncoder *rotaryEncoder, int encoderIndex = -1); void removePositionSwitch(int positionSwitchIndex); void removeStepper(byte stepperConfigurationIndex); void removeRotaryEncoder(byte rotaryEncoderConfigurationIndex); void getFormattedPositionSwitchStatusRegister(byte registerIndex, String &output); void printPositionSwitchStatus(); void performEmergencyStop(int stepperIndex = -1); void revokeEmergencyStop(); void start(); void stop(); byte getPositionSwitchStatus(int positionSwitchIndex); signed char updateSwitchStatusRegister(); String getIpAddress(); ESPStepperMotorServer_Configuration *getCurrentServerConfiguration(); ESPStepperMotorServer_CLI *getCLIHandler() const; void requestReboot(String rebootReason); bool isSPIFFSMounted(); //delegator functions only void setLogLevel(byte); void getServerStatusAsJsonString(String &statusString); byte getFirstAvailableConfigurationSlotForRotaryEncoder(); bool isIoPinUsed(int); // // public member variables // const char *defaultConfigurationFilename = "/config.json"; int wifiClientConnectionTimeoutSeconds = 25; // a boolean indicating if a position switch that has been configure as emegrency switch, has been triggered volatile boolean emergencySwitchIsActive = false; const char *version = "0.4.7"; private: void scanWifiNetworks(); void connectToWifiNetwork(); void startAccessPoint(); #ifndef ESPStepperMotorServer_COMPILE_NO_WEB void startWebserver(); void registerWebInterfaceUrls(); bool checkIfGuiExistsInSpiffs(); bool downloadFileToSpiffs(const char *url, const char *targetPath); #endif void startSPIFFS(); void printSPIFFSStats(); int getSPIFFSFreeSpace(); void printSPIFFSRootFolderContents(); void setupAllIOPins(); void setupPositionSwitchIOPin(ESPStepperMotorServer_PositionSwitch *posSwitch); void setupRotaryEncoderIOPin(ESPStepperMotorServer_RotaryEncoder *rotaryEncoder); void detachInterruptForPositionSwitch(ESPStepperMotorServer_PositionSwitch *posSwitch); void detachInterruptForRotaryEncoder(ESPStepperMotorServer_RotaryEncoder *rotaryEncoder); void detachAllInterrupts(); void attachAllInterrupts(); void setPositionSwitchStatus(int positionSwitchIndex, byte status); // ISR handling static void staticPositionSwitchISR(); static void staticEmergencySwitchISR(); static void staticLimitSwitchISR_POS_END(); static void staticLimitSwitchISR_POS_BEGIN(); static void staticLimitSwitchISR_COMBINED(); static void staticRotaryEncoderISR(); void internalEmergencySwitchISR(); void internalSwitchISR(byte switchType); void internalRotaryEncoderISR(); // // private member variables // byte enabledServices; boolean isWebserverEnabled = false; boolean isRestApiEnabled = false; boolean isCLIEnabled = false; boolean isServerStarted = false; boolean isSPIFFSactive = false; boolean _isRebootScheduled = false; ESPStepperMotorServer_Configuration *serverConfiguration; #ifndef ESPStepperMotorServer_COMPILE_NO_WEB ESPStepperMotorServer_WebInterface *webInterfaceHandler; ESPStepperMotorServer_RestAPI *restApiHandler; AsyncWebServer *httpServer; AsyncWebSocket *webSocketServer; #endif ESPStepperMotorServer_CLI *cliHandler; ESPStepperMotorServer_MotionController *motionControllerHandler; static ESPStepperMotorServer *anchor; //used for self-reference in ISR // the button status register for all configured button switches volatile byte buttonStatus[ESPServerSwitchStatusRegisterCount] = {0}; }; // ------------------------------------ End --------------------------------- #endif ================================================ FILE: src/ESPStepperMotorServer_CLI.cpp ================================================ // ********************************************************* // * * // * ESP32 Stepper Motor Command Line Interface * // * * // * Copyright (c) Paul Kerspe, 2019 * // * * // ********************************************************** // MIT License // // Copyright (c) 2019 Paul Kerspe // // Permission is hereby granted, free of charge, to any person obtaining a copy // of this software and associated documentation files (the "Software"), to deal // in the Software without restriction, including without limitation the rights // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell // copies of the Software, and to permit persons to whom the Software is furnished // to do so, subject to the following conditions: // // The above copyright notice and this permission notice shall be included in all // copies or substantial portions of the Software. // // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE // SOFTWARE. #include #define CR '\r' #define LF '\n' #define BS '\b' #define NULLCHAR '\0' #define COMMAND_BUFFER_LENGTH 50 //length of serial buffer for incoming commands // --------------------------------------------------------------------------------- // Setup functions // --------------------------------------------------------------------------------- // // constructor for the command line interface module // creates a freeRTOS Task that runs in the background and polls the serial interface for input to parse // ESPStepperMotorServer_CLI::ESPStepperMotorServer_CLI(ESPStepperMotorServer *serverRef) { this->serverRef = serverRef; } ESPStepperMotorServer_CLI::~ESPStepperMotorServer_CLI() { if (this->xHandle != NULL) { this->stop(); } } void ESPStepperMotorServer_CLI::start() { xTaskCreate( ESPStepperMotorServer_CLI::processSerialInput, /* Task function. */ "SerialInterfacePoller", /* String with name of task. */ 10000, /* Stack size in bytes. */ this, /* Parameter passed as input of the task */ 1, /* Priority of the task. */ &this->xHandle); /* Task handle. */ this->registerCommands(); ESPStepperMotorServer_Logger::logInfof("Command Line Interface started, registered %i commands. Type 'help' to get a list of all supported commands\n", this->commandCounter); } void ESPStepperMotorServer_CLI::stop() { vTaskDelete(this->xHandle); this->xHandle = NULL; ESPStepperMotorServer_Logger::logInfo("Command Line Interface stopped"); } void ESPStepperMotorServer_CLI::executeCommand(String cmd) { char cmdCharArray[cmd.length() + 1]; strcpy(cmdCharArray, cmd.c_str()); char *pureCommand = strtok(cmdCharArray, _CMD_PARAM_SEPARATOR); char *arguments = strtok(NULL, "="); // first try the built in commands for (int i = 0; i < this->commandCounter; i++) { if (this->allRegisteredCommands[i].command.equals(pureCommand) || this->allRegisteredCommands[i].shortCut.equals(pureCommand)) { (this->*command_functions[i])(pureCommand, arguments); return; } } // next, see if it's a user defined command for (int i = 0; i < this->userCommandCounter; i++) { if (this->allRegisteredUserCommands[i].command.equals(pureCommand) || this->allRegisteredUserCommands[i].shortCut.equals(pureCommand)) { (this->user_command_functions[i])(pureCommand, arguments); return; } } Serial.printf("error: Command '%s' is unknown\n", cmd.c_str()); } void ESPStepperMotorServer_CLI::processSerialInput(void *parameter) { ESPStepperMotorServer_CLI *ref = static_cast(parameter); char commandLine[COMMAND_BUFFER_LENGTH + 1]; uint8_t charsRead = 0; char buffer[2]; char c; while (true) { while (Serial.available()) { Serial.readBytes(buffer, 1); //using this step to avoid the annoying warnings of code quality check to Check buffer boundaries c = buffer[0]; switch (c) { case CR: //likely have full command in buffer now, commands are terminated by CR and/or LS case LF: commandLine[charsRead] = NULLCHAR; //null terminate our command char array if (charsRead > 0) { charsRead = 0; //charsRead behaves like 'static' in this task, so have to reset try { ref->executeCommand(String(commandLine)); } catch (...) { ESPStepperMotorServer_Logger::logWarningf("Caught an exception wil trying to execute command line '%s'\n", commandLine); } } break; case BS: // handle backspace in input: put a blank in last char if (charsRead > 0) { //and adjust commandLine and charsRead commandLine[--charsRead] = NULLCHAR; } break; default: if (charsRead < COMMAND_BUFFER_LENGTH) { commandLine[charsRead++] = c; } commandLine[charsRead] = NULLCHAR; //just in case break; } } vTaskDelay(10); } } // --------------------------------------------------------------------------------- // Command interpreter functions // --------------------------------------------------------------------------------- void ESPStepperMotorServer_CLI::registerCommands() { #ifdef ESPStepperMotorServer_COMPILE_NO_CLI_HELP String emptyHelp = String(""); #endif #ifdef ESPStepperMotorServer_COMPILE_NO_CLI_HELP this->registerNewCommand({String("help"), String("h"), emptyHelp, false}, &ESPStepperMotorServer_CLI::cmdHelp); this->registerNewCommand({String("moveby"), String("mb"), emptyHelp, true}, &ESPStepperMotorServer_CLI::cmdMoveBy); this->registerNewCommand({String("moveto"), String("mt"), emptyHelp, true}, &ESPStepperMotorServer_CLI::cmdMoveTo); this->registerNewCommand({String("config"), String("c"), emptyHelp, false}, &ESPStepperMotorServer_CLI::cmdPrintConfig); this->registerNewCommand({String("emergencystop"), String("es"), emptyHelp, false}, &ESPStepperMotorServer_CLI::cmdEmergencyStop); this->registerNewCommand({String("revokeemergencystop"), String("res"), emptyHelp, false}, &ESPStepperMotorServer_CLI::cmdRevokeEmergencyStop); this->registerNewCommand({String("position"), String("p"), emptyHelp, true}, &ESPStepperMotorServer_CLI::cmdGetPosition); this->registerNewCommand({String("velocity"), String("v"), emptyHelp, true}, &ESPStepperMotorServer_CLI::cmdGetCurrentVelocity); this->registerNewCommand({String("removeswitch"), String("rsw"), emptyHelp, true}, &ESPStepperMotorServer_CLI::cmdRemoveSwitch); this->registerNewCommand({String("removestepper"), String("rs"), emptyHelp, true}, &ESPStepperMotorServer_CLI::cmdRemoveStepper); this->registerNewCommand({String("removeencoder"), String("re"), emptyHelp, true}, &ESPStepperMotorServer_CLI::cmdRemoveEncoder); this->registerNewCommand({String("reboot"), String("r"), emptyHelp, false}, &ESPStepperMotorServer_CLI::cmdReboot); this->registerNewCommand({String("save"), String("s"), emptyHelp, false}, &ESPStepperMotorServer_CLI::cmdSaveConfiguration); this->registerNewCommand({String("stop"), String("st"), emptyHelp, false}, &ESPStepperMotorServer_CLI::cmdStopServer); this->registerNewCommand({String("loglevel"), String("ll"), emptyHelp, true}, &ESPStepperMotorServer_CLI::cmdSetLogLevel); this->registerNewCommand({String("serverstatus"), String("ss"), emptyHelp, false}, &ESPStepperMotorServer_CLI::cmdServerStatus); this->registerNewCommand({String("switchstatus"), String("pss"), emptyHelp, false}, &ESPStepperMotorServer_CLI::cmdSwitchStatus); this->registerNewCommand({String("setapname"), String("san"), emptyHelp, true}, &ESPStepperMotorServer_CLI::cmdSetApName); this->registerNewCommand({String("setappwd"), String("sap"), emptyHelp, true}, &ESPStepperMotorServer_CLI::cmdSetApPassword); this->registerNewCommand({String("setwifissid"), String("sws"), emptyHelp, true}, &ESPStepperMotorServer_CLI::cmdSetSSID); this->registerNewCommand({String("setwifipwd"), String("swp"), emptyHelp, true}, &ESPStepperMotorServer_CLI::cmdSetWifiPassword); #else this->registerNewCommand({String("help"), String("h"), String("show a list of all available commands"), false}, &ESPStepperMotorServer_CLI::cmdHelp); this->registerNewCommand({String("moveby"), String("mb"), String("move by a specified number of units. requires the id of the stepper to move, the amount of movement and also optional the unit for the movement (mm, steps, revs). If no unit is specified steps will be assumed as unit. Optionally you can also set the speed in steps/second, acceleration and deceleration, each in steps/second/second). Set speeds, acceleration and deceleration are rememebered until overwritten again. E.g. mb=0&v:-100&u:mm&s:200 to move the stepper with id 0 by -100 mm with a speed of 200 steps per second"), true}, &ESPStepperMotorServer_CLI::cmdMoveBy); this->registerNewCommand({String("moveto"), String("mt"), String("move to an absolute position. requires the id of the stepper to move, the amount of movement and also optional the unit for the movement (mm, steps, revs). If no unit is specified steps will be assumed as unit. Optionally you can also set the speed in steps/second, acceleration and deceleration, each in steps/second/second). Set speeds, acceleration and deceleration are rememebered until overwritten again. E.g. mt=0&v:100&u:revs&a:100 to move the stepper with id 0 to the absolute position at 100 revolutions with an acceleration of 100 steps per second^2"), true}, &ESPStepperMotorServer_CLI::cmdMoveTo); this->registerNewCommand({String("config"), String("c"), String("print the current configuration to the console as JSON formatted string"), false}, &ESPStepperMotorServer_CLI::cmdPrintConfig); this->registerNewCommand({String("emergencystop"), String("es"), String("trigger emergency stop for all connected steppers. This will clear all target positions and stop the motion controller module immediately. In order to proceed normal operation after this command has been issued, you need to call the revokeemergencystop [res] command"), false}, &ESPStepperMotorServer_CLI::cmdEmergencyStop); this->registerNewCommand({String("revokeemergencystop"), String("res"), String("revoke a previously triggered emergency stop. This must be called before any motions can proceed after a call to the emergencystop command"), false}, &ESPStepperMotorServer_CLI::cmdRevokeEmergencyStop); this->registerNewCommand({String("position"), String("p"), String("get the current position of a specific stepper or all steppers if no explicit index is given (e.g. by calling 'pos' or 'pos=&u:mm'). If no parameter for the unit is provided, will return the position in steps. Requires the ID of the stepper to get the position for as parameter and optional the unit using 'u:mm'/'u:steps'/'u:revs'. E.g.: p=0&u:steps to return the current position of stepper with id = 0 with unit 'steps'"), true}, &ESPStepperMotorServer_CLI::cmdGetPosition); this->registerNewCommand({String("velocity"), String("v"), String("get the current velocity of a specific stepper or all steppers if no explicit index is given (e.g. by calling 'pos' or 'pos=&u:mm'). If no parameter for the unit is provided, will return the position in steps. Requires the ID of the stepper to get the velocity for as parameter and optional the unit using 'u:mm'/'u:steps'/'u:revs'. E.g.: v=0&u:mm to return the velocity in mm per second of stepper with id = 0"), true}, &ESPStepperMotorServer_CLI::cmdGetCurrentVelocity); this->registerNewCommand({String("removeswitch"), String("rsw"), String("remove an existing switch configuration. E.g. rsw=0 to remove the switch with the ID 0"), true}, &ESPStepperMotorServer_CLI::cmdRemoveSwitch); this->registerNewCommand({String("removestepper"), String("rs"), String("remove and existing stepper configuration. E.g. rs=0 to remove the stepper config with the ID 0"), true}, &ESPStepperMotorServer_CLI::cmdRemoveStepper); this->registerNewCommand({String("removeencoder"), String("re"), String("remove an existing rotary encoder configuration. E.g. re=0 to remove the encoder with the ID 0"), true}, &ESPStepperMotorServer_CLI::cmdRemoveEncoder); this->registerNewCommand({String("reboot"), String("r"), String("reboot the ESP (config changes that have not been saved will be lost)"), false}, &ESPStepperMotorServer_CLI::cmdReboot); this->registerNewCommand({String("save"), String("s"), String("save the current configuration to the SPIFFS in config.json"), false}, &ESPStepperMotorServer_CLI::cmdSaveConfiguration); this->registerNewCommand({String("stop"), String("st"), String("stop the stepper server (also stops the CLI!)"), false}, &ESPStepperMotorServer_CLI::cmdStopServer); this->registerNewCommand({String("loglevel"), String("ll"), String("set or get the current log level for serial output. valid values to set are: 1 (Warning) - 4 (ALL). E.g. to set to log level DEBUG use ll=3 to get the current loglevel call without parameter"), true}, &ESPStepperMotorServer_CLI::cmdSetLogLevel); this->registerNewCommand({String("serverstatus"), String("ss"), String("print status details of the server as JSON formated string"), false}, &ESPStepperMotorServer_CLI::cmdServerStatus); this->registerNewCommand({String("switchstatus"), String("pss"), String("print the status of all input switches as JSON formated string"), false}, &ESPStepperMotorServer_CLI::cmdSwitchStatus); this->registerNewCommand({String("setapname"), String("san"), String("set the name of the access point to be opened up by the esp (if in AP mode)"), true}, &ESPStepperMotorServer_CLI::cmdSetApName); this->registerNewCommand({String("setappwd"), String("sap"), String("set the password for the access point to be opened by the esp"), true}, &ESPStepperMotorServer_CLI::cmdSetApPassword); this->registerNewCommand({String("setwifissid"), String("sws"), String("set the SSID of the WiFi to connect to (if in client mode)"), true}, &ESPStepperMotorServer_CLI::cmdSetSSID); this->registerNewCommand({String("setwifipwd"), String("swp"), String("set the password of the Wifi network to connect to"), true}, &ESPStepperMotorServer_CLI::cmdSetWifiPassword); #ifndef ESPStepperMotorServer_COMPILE_NO_WEB this->registerNewCommand({String("sethttpport"), String("shp"), String("set the http port to listen for for the web interface"), true}, &ESPStepperMotorServer_CLI::cmdSetHttpPort); #endif #endif //TODO: implement missing cmd functions // this->registerNewCommand("addswitch", "asw", 1, "add a new switch configuration", &ESPStepperMotorServer_CLI::cmdAddSwitch); // this->registerNewCommand("addstepper", "as", 1, "add a new stepper configuration", &ESPStepperMotorServer_CLI::cmdAddStepper); // this->registerNewCommand("addencoder", "ae", 1, "add a new rotary encoder configuration", &ESPStepperMotorServer_CLI::cmdAddEncoder); // this->registerNewCommand("listencoders", "le", 0, "list all configured rotary encoders", &ESPStepperMotorServer_CLI::cmdListEncoders); // this->registerNewCommand("liststeppers", "ls", 0, "list all configured steppers", &ESPStepperMotorServer_CLI::cmdListSteppers); // this->registerNewCommand("listswitches", "lsw", 0, "list all configured input switches", &ESPStepperMotorServer_CLI::cmdListSwitches); // this->registerNewCommand("returnhome", "rh", 1, "Return to the home position (only possible if a homing switch is connected). Requires the ID of the stepper to get the position for as parameter. E.g.: rh=0", &ESPStepperMotorServer_CLI::cmdReturnHome); // create set wifi mode function } void ESPStepperMotorServer_CLI::registerNewCommand(commandDetailsStructure commandDetails, void (ESPStepperMotorServer_CLI::*cmdFunction)(char *, char *)) { if (this->commandCounter < MAX_CLI_CMD_COUNTER) { //check if command is already registered for (int i = 0; i < this->commandCounter; i++) { if (this->allRegisteredCommands[i].command.equals(commandDetails.command) || this->allRegisteredCommands[i].shortCut.equals(commandDetails.shortCut)) { ESPStepperMotorServer_Logger::logWarningf("A command with the same name / shortcut is already registered. Will not add the command '%s' [%s] to the list of registered commands", commandDetails.command, commandDetails.shortCut); return; } } this->allRegisteredCommands[this->commandCounter] = commandDetails; this->command_functions[this->commandCounter] = cmdFunction; this->commandCounter++; } else { ESPStepperMotorServer_Logger::logWarningf("The maximum number of CLI commands has been exceeded. You need to increase the MAX_CLI_CMD_COUNTER value to add more than %i commands\n", MAX_CLI_CMD_COUNTER); } } void ESPStepperMotorServer_CLI::registerNewUserCommand(commandDetailsStructure commandDetails, void (*cmdFunction)(char *, char *)) { if (this->userCommandCounter < MAX_CLI_USER_CMD_COUNTER) { //check if command is already registered as a built in command for (int i = 0; i < this->commandCounter; i++) { if (this->allRegisteredCommands[i].command.equals(commandDetails.command) || this->allRegisteredCommands[i].shortCut.equals(commandDetails.shortCut)) { ESPStepperMotorServer_Logger::logWarningf("A command with the same name / shortcut is already registered. Will not add the command '%s' [%s] to the list of registered user commands", commandDetails.command, commandDetails.shortCut); return; } } // next check if it's already registered as a user command for (int i = 0; i < this->userCommandCounter; i++) { if (this->allRegisteredUserCommands[i].command.equals(commandDetails.command) || this->allRegisteredUserCommands[i].shortCut.equals(commandDetails.shortCut)) { ESPStepperMotorServer_Logger::logWarningf("A user command with the same name / shortcut is already registered. Will not add the command '%s' [%s] to the list of registered user commands", commandDetails.command, commandDetails.shortCut); return; } } this->allRegisteredUserCommands[this->userCommandCounter] = commandDetails; this->user_command_functions[this->userCommandCounter] = cmdFunction; this->userCommandCounter++; } else { ESPStepperMotorServer_Logger::logWarningf("The maximum number of CLI user commands has been exceeded. You need to increase the MAX_CLI_USER_CMD_COUNTER value to add more than %i commands\n", MAX_CLI_USER_CMD_COUNTER); } } void ESPStepperMotorServer_CLI::cmdPrintConfig(char *cmd, char *args) { this->serverRef->getCurrentServerConfiguration()->printCurrentConfigurationAsJsonToSerial(); } const char *setterConfirmationTemplate = "%s set to %s (please save and reboot for the changes to take effect)\n"; const char *setterMissingParameterTemplate = "No or invalid value given as parameter. Usage is %s=\n"; void ESPStepperMotorServer_CLI::cmdSetApName(char *cmd, char *args) { if (args != NULL) { this->serverRef->setAccessPointName(args); Serial.printf(setterConfirmationTemplate, "AP name", args); } else { Serial.printf(setterMissingParameterTemplate, cmd); } } void ESPStepperMotorServer_CLI::cmdSetApPassword(char *cmd, char *args) { if (args != NULL) { this->serverRef->setAccessPointPassword(args); Serial.printf(setterConfirmationTemplate, "AP password", args); } else { Serial.printf(setterMissingParameterTemplate, cmd); } } #ifndef ESPStepperMotorServer_COMPILE_NO_WEB void ESPStepperMotorServer_CLI::cmdSetHttpPort(char *cmd, char *args) { int port = (int)(String(args)).toInt(); if (port >= 80) { this->serverRef->setHttpPort(port); Serial.printf(setterConfirmationTemplate, "HTTP port", args); } else { Serial.printf(setterMissingParameterTemplate, cmd); } } #endif void ESPStepperMotorServer_CLI::cmdSetSSID(char *cmd, char *args) { if (args != NULL) { this->serverRef->setWifiSSID(args); Serial.printf(setterConfirmationTemplate, "WiFi SSID", args); } else { Serial.printf(setterMissingParameterTemplate, cmd); } } void ESPStepperMotorServer_CLI::cmdSetWifiPassword(char *cmd, char *args) { if (args != NULL) { this->serverRef->setWifiPassword(args); Serial.printf(setterConfirmationTemplate, "WiFi password", args); } else { Serial.printf(setterMissingParameterTemplate, cmd); } } void ESPStepperMotorServer_CLI::cmdHelp(char *cmd, char *args) { #ifdef ESPStepperMotorServer_COMPILE_NO_CLI_HELP Serial.println(" []"); #else Serial.println("\n-------- ESP-StepperMotor-Server-CLI Help -----------\nThe following commands are available:\n"); Serial.println(" []: "); #endif Serial.println("\nBuilt in commands:"); for (int i = 0; i < this->commandCounter; i++) { const char *hint = this->allRegisteredCommands[i].hasParameters ? "*" : ""; const char *tabString = (this->allRegisteredCommands[i].command.length() + this->allRegisteredCommands[i].shortCut.length() < 12) ? "\t" : ""; Serial.printf("%s [%s]%s:\t%s%s\n", this->allRegisteredCommands[i].command.c_str(), this->allRegisteredCommands[i].shortCut.c_str(), hint, tabString, this->allRegisteredCommands[i].description.c_str()); } if (this->userCommandCounter > 0) { Serial.println("\nUser commands:"); for (int i = 0; i < this->userCommandCounter; i++) { const char *hint = this->allRegisteredUserCommands[i].hasParameters ? "*" : ""; const char *tabString = (this->allRegisteredUserCommands[i].command.length() + this->allRegisteredUserCommands[i].shortCut.length() < 12) ? "\t" : ""; Serial.printf("%s [%s]%s:\t%s%s\n", this->allRegisteredUserCommands[i].command.c_str(), this->allRegisteredUserCommands[i].shortCut.c_str(), hint, tabString, this->allRegisteredUserCommands[i].description.c_str()); } } #ifndef ESPStepperMotorServer_COMPILE_NO_CLI_HELP Serial.println("\ncommmands marked with a * require input parameters.\nParameters are provided with the command separarted by a = for the primary parameter.\nSecondary parameters are provided in the format '&:'\n"); Serial.println("-------------------------------------------------------"); #endif } void ESPStepperMotorServer_CLI::cmdReboot(char *cmd, char *args) { Serial.println("initiating restart"); ESP.restart(); } void ESPStepperMotorServer_CLI::cmdSwitchStatus(char *cmd, char *args) { this->serverRef->printPositionSwitchStatus(); } void ESPStepperMotorServer_CLI::cmdServerStatus(char *cmd, char *args) { String result; this->serverRef->getServerStatusAsJsonString(result); Serial.println(result); } void ESPStepperMotorServer_CLI::cmdStopServer(char *cmd, char *args) { this->serverRef->stop(); Serial.println(cmd); } void ESPStepperMotorServer_CLI::cmdEmergencyStop(char *cmd, char *args) { this->serverRef->performEmergencyStop(); Serial.println(cmd); } void ESPStepperMotorServer_CLI::cmdRevokeEmergencyStop(char *cmd, char *args) { this->serverRef->revokeEmergencyStop(); Serial.println(cmd); } void ESPStepperMotorServer_CLI::cmdRemoveSwitch(char *cmd, char *args) { unsigned int id = (String(args)).toInt(); if (id > ESPServerMaxSwitches || !this->serverRef->getCurrentServerConfiguration()->getSwitch((byte)id)) { Serial.println("error: invalid switch id given"); } else { this->serverRef->removePositionSwitch((byte)id); Serial.println(cmd); } } void ESPStepperMotorServer_CLI::cmdRemoveStepper(char *cmd, char *args) { int stepperid = this->getValidStepperIdFromArg(args); if (stepperid > -1) { this->serverRef->removeStepper((byte)stepperid); Serial.println(cmd); } } void ESPStepperMotorServer_CLI::cmdRemoveEncoder(char *cmd, char *args) { unsigned int id = (String(args)).toInt(); if (id > ESPServerMaxRotaryEncoders || !this->serverRef->getCurrentServerConfiguration()->getRotaryEncoder((byte)id)) { Serial.println("error: invalid encoder id given"); } else { this->serverRef->removeRotaryEncoder((byte)id); Serial.println(cmd); } } void ESPStepperMotorServer_CLI::cmdGetCurrentVelocity(char *cmd, char *args) { ESPStepperMotorServer_Configuration *config = this->serverRef->getCurrentServerConfiguration(); int stepperid = this->getValidStepperIdFromArg(args); char unit[10]; this->getUnitWithFallback(args, unit); if (stepperid > -1) { if (strcmp(unit, "mm") == 0) Serial.printf("%f mm/s\n", config->getStepperConfiguration((byte)stepperid)->getFlexyStepper()->getCurrentVelocityInMillimetersPerSecond()); else if (strcmp(unit, "revs") == 0) Serial.printf("%f revs/s\n", config->getStepperConfiguration((byte)stepperid)->getFlexyStepper()->getCurrentVelocityInRevolutionsPerSecond()); else Serial.printf("%f steps/s\n", config->getStepperConfiguration((byte)stepperid)->getFlexyStepper()->getCurrentVelocityInStepsPerSecond()); } else { #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG ESPStepperMotorServer_Logger::logDebugf("%s called without parameter for stepper index\n", cmd); #endif for (stepperid = 0; stepperid < ESPServerMaxSteppers; stepperid++) { ESPStepperMotorServer_StepperConfiguration *stepper = this->serverRef->getCurrentServerConfiguration()->getStepperConfiguration(stepperid); if (stepper) { if (strcmp(unit, "mm") == 0) Serial.printf("%i:%f mm/s\n", stepperid, stepper->getFlexyStepper()->getCurrentVelocityInMillimetersPerSecond()); else if (strcmp(unit, "revs") == 0) Serial.printf("%i:%f revs/s\n", stepperid, stepper->getFlexyStepper()->getCurrentVelocityInRevolutionsPerSecond()); else Serial.printf("%i:%f steps/s\n", stepperid, stepper->getFlexyStepper()->getCurrentVelocityInStepsPerSecond()); } } } } void ESPStepperMotorServer_CLI::cmdGetPosition(char *cmd, char *args) { ESPStepperMotorServer_Configuration *config = this->serverRef->getCurrentServerConfiguration(); int stepperid = this->getValidStepperIdFromArg(args); char unit[10]; this->getUnitWithFallback(args, unit); if (stepperid > -1) { if (strcmp(unit, "mm") == 0) Serial.printf("%f mm\n", config->getStepperConfiguration((byte)stepperid)->getFlexyStepper()->getCurrentPositionInMillimeters()); else if (strcmp(unit, "revs") == 0) Serial.printf("%f revs\n", config->getStepperConfiguration((byte)stepperid)->getFlexyStepper()->getCurrentPositionInRevolutions()); else Serial.printf("%ld steps\n", config->getStepperConfiguration((byte)stepperid)->getFlexyStepper()->getCurrentPositionInSteps()); } else { #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG ESPStepperMotorServer_Logger::logDebugf("%s called without parameter for stepper index\n", cmd); #endif for (stepperid = 0; stepperid < ESPServerMaxSteppers; stepperid++) { ESPStepperMotorServer_StepperConfiguration *stepper = config->getStepperConfiguration(stepperid); if (stepper) { if (strcmp(unit, "mm") == 0) Serial.printf("%i:%f mm\n", stepperid, stepper->getFlexyStepper()->getCurrentPositionInMillimeters()); else if (strcmp(unit, "revs") == 0) Serial.printf("%i:%f revs\n", stepperid, stepper->getFlexyStepper()->getCurrentPositionInRevolutions()); else Serial.printf("%i:%ld steps\n", stepperid, stepper->getFlexyStepper()->getCurrentPositionInSteps()); } } } } void ESPStepperMotorServer_CLI::setMoveSpeedAccelHelper(ESP_FlexyStepper *flexyStepper, char *args) { char buffer[20]; this->getParameterValue(args, "s", buffer); if (buffer[0] != NULLCHAR) { float speed = (String(buffer).toFloat()); if (speed > 0) { #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG ESPStepperMotorServer_Logger::logDebugf("Setting speed to %f steps / second\n", speed); #endif flexyStepper->setSpeedInStepsPerSecond(speed); } } this->getParameterValue(args, "a", buffer); if (buffer[0] != NULLCHAR) { float accel = (String(buffer).toFloat()); if (accel > 0) { #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG ESPStepperMotorServer_Logger::logDebugf("Setting acceleration to %f steps / second^2\n", accel); #endif flexyStepper->setAccelerationInStepsPerSecondPerSecond(accel); //in case deceleration is not explicitly given, we just use the same value flexyStepper->setDecelerationInStepsPerSecondPerSecond(accel); } } this->getParameterValue(args, "d", buffer); if (buffer[0] != NULLCHAR) { float decel = (String(buffer).toFloat()); if (decel > 0) { #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG ESPStepperMotorServer_Logger::logDebugf("Setting deceleration to %f steps / second^2\n", decel); #endif flexyStepper->setDecelerationInStepsPerSecondPerSecond(decel); } } } void ESPStepperMotorServer_CLI::cmdMoveTo(char *cmd, char *args) { int stepperid = this->getValidStepperIdFromArg(args); if (stepperid > -1) { ESP_FlexyStepper *flexyStepper = this->serverRef->getCurrentServerConfiguration()->getStepperConfiguration(stepperid)->getFlexyStepper(); this->setMoveSpeedAccelHelper(flexyStepper, args); char value[20]; this->getParameterValue(args, "v", value); if (value[0] != NULLCHAR) { char unit[10]; this->getParameterValue(args, "u", unit); if (unit[0] == NULLCHAR || strcmp(unit, "steps") == 0) { if (unit[0] == NULLCHAR) { Serial.println("no unit provided, will use 'steps' as default"); } flexyStepper->setTargetPositionInSteps((String(value).toInt())); } else if (strcmp(unit, "revs") == 0) { flexyStepper->setTargetPositionInRevolutions((String(value).toFloat())); } else if (strcmp(unit, "mm") == 0) { flexyStepper->setTargetPositionInMillimeters((String(value).toFloat())); } else { Serial.println("error: provided unit not supported. Must be one of mm, steps or revs"); return; } Serial.println(cmd); } else { Serial.println("error: missing required v parameter"); } } } void ESPStepperMotorServer_CLI::cmdMoveBy(char *cmd, char *args) { int stepperid = this->getValidStepperIdFromArg(args); #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG ESPStepperMotorServer_Logger::logDebugf("%s called for stepper id %i\n", cmd, stepperid); #endif if (stepperid > -1) { ESP_FlexyStepper *flexyStepper = this->serverRef->getCurrentServerConfiguration()->getStepperConfiguration(stepperid)->getFlexyStepper(); this->setMoveSpeedAccelHelper(flexyStepper, args); char value[20]; this->getParameterValue(args, "v", value); if (value[0] != NULLCHAR) { #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG ESPStepperMotorServer_Logger::logDebugf("cmdMoveBy called with v = %s\n", value); #endif char unit[10]; this->getParameterValue(args, "u", unit); if (unit[0] == NULLCHAR || strcmp(unit, "steps") == 0) { if (unit[0] == NULLCHAR) { Serial.println("no unit provided, will use 'steps' as default"); } int targetPosition = (String(value).toInt()); #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG ESPStepperMotorServer_Logger::logDebugf("Setting target position to %i steps\n", targetPosition); #endif flexyStepper->setTargetPositionRelativeInSteps(targetPosition); } else if (strcmp(unit, "revs") == 0) { float targetPosition = (String(value).toFloat()); #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG ESPStepperMotorServer_Logger::logDebugf("Setting target position to %f revs\n", targetPosition); #endif flexyStepper->setTargetPositionRelativeInRevolutions(targetPosition); } else if (strcmp(unit, "mm") == 0) { float targetPosition = (String(value).toFloat()); #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG ESPStepperMotorServer_Logger::logDebugf("Setting target position to %f mm\n", targetPosition); #endif flexyStepper->setTargetPositionRelativeInMillimeters(targetPosition); } else { Serial.println("error: provided unit not supported. Must be one of mm, steps or revs"); return; } Serial.println(cmd); } else { Serial.println("error: missing required v parameter"); } } } void ESPStepperMotorServer_CLI::cmdSaveConfiguration(char *cmd, char *args) { if (this->serverRef->getCurrentServerConfiguration()->saveCurrentConfiguationToSpiffs()) { Serial.println(cmd); } else { Serial.println("error: saving configuration to SPIFFS failed"); } } void ESPStepperMotorServer_CLI::cmdSetLogLevel(char *cmd, char *args) { unsigned int logLevelToSet = (String(args)).toInt(); if (logLevelToSet == 0) { Serial.printf("%s=%i\n", cmd, ESPStepperMotorServer_Logger::getLogLevel()); } else { if (logLevelToSet > ESPServerLogLevel_ALL || logLevelToSet < ESPServerLogLevel_WARNING) { Serial.printf("error: Invalid log level given. Must be in the range of %i (Warning) and %i (All)\n", ESPServerLogLevel_WARNING, ESPServerLogLevel_ALL); } ESPStepperMotorServer_Logger::setLogLevel(logLevelToSet); } } /** * convert given char* to int value and check if it represents a valid stepper config id (within the allowed limits and with an existing stepper configuation existing) * -1 is returned if not valid and an error os printed to the serial interface */ int ESPStepperMotorServer_CLI::getValidStepperIdFromArg(char *arg) { if (arg && isdigit(arg[0])) { int id = (String(arg)).toInt(); #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG ESPStepperMotorServer_Logger::logDebugf("extracted stepper id %i from argument string %s\n", id, arg); #endif if (id > ESPServerMaxSteppers || !this->serverRef->getCurrentServerConfiguration()->getStepperConfiguration((byte)id)) { Serial.println("error: invalid stepper id given"); return -1; } return (byte)id; } #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG else { ESPStepperMotorServer_Logger::logDebug("no argument string given to extract stepper id from, will return -1"); } #endif return -1; } /** * helper function to extract parameters and values from the given argument string */ void ESPStepperMotorServer_CLI::getParameterValue(const char *args, const char *parameterNameToGetValueFor, char *result) { if (args == NULL) { #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG ESPStepperMotorServer_Logger::logDebugf("getParameterValue called with on NULL and %s\n", parameterNameToGetValueFor); #endif strcpy(result, ""); return; } #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG ESPStepperMotorServer_Logger::logDebugf("getParameterValue called with %s and %s\n", args, parameterNameToGetValueFor); #endif char *parameterValue; char *save_ptr; String argumentString = String(args); char workingCopy[argumentString.length() + 1]; strcpy(workingCopy, args); char *keyValuePairString = strtok_r(workingCopy, this->_PARAM_PARAM_SEPRATOR, &save_ptr); while (keyValuePairString != NULL) { #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG ESPStepperMotorServer_Logger::logDebugf("Found a key value pair: %s\n", keyValuePairString); #endif char *restKeyValuePair = keyValuePairString; char *parameterName = strtok_r(restKeyValuePair, this->_PARAM_VALUE_SEPRATOR, &restKeyValuePair); if (parameterName != NULL) { #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG ESPStepperMotorServer_Logger::logDebugf("Found parameter '%s'\n", parameterName); #endif if (strcmp(parameterName, parameterNameToGetValueFor) == 0) { if (restKeyValuePair && strcmp(restKeyValuePair, "") != 0) { parameterValue = strtok_r(restKeyValuePair, this->_PARAM_VALUE_SEPRATOR, &restKeyValuePair); #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG ESPStepperMotorServer_Logger::logDebugf("Found matching parameter: %s with value %s\n", parameterName, parameterValue); #endif strcpy(result, parameterValue); return; } } #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG else { ESPStepperMotorServer_Logger::logDebug("parameter did not match requested parameter"); } #endif } keyValuePairString = strtok_r(NULL, this->_PARAM_PARAM_SEPRATOR, &save_ptr); } #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG ESPStepperMotorServer_Logger::logDebug("No match found"); #endif strcpy(result, ""); } ////// internal helpers to prevent code duplication void ESPStepperMotorServer_CLI::getUnitWithFallback(char *args, char *unit) { this->getParameterValue(args, "u", unit); if (unit[0] == NULLCHAR) { #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG ESPStepperMotorServer_Logger::logDebug("no unit provided, will use 'steps' as default"); #endif strcpy(unit, "steps"); } } // -------------------------------------- End -------------------------------------- ================================================ FILE: src/ESPStepperMotorServer_CLI.h ================================================ // ****************************************************************** // * * // * Header file for ESPStepperMotorServer_CLI.cpp * // * * // * Copyright (c) Paul Kerspe, 2019 * // * * // ****************************************************************** // MIT License // // Copyright (c) 2019 Paul Kerspe // // Permission is hereby granted, free of charge, to any person obtaining a copy // of this software and associated documentation files (the "Software"), to deal // in the Software without restriction, including without limitation the rights // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell // copies of the Software, and to permit persons to whom the Software is furnished // to do so, subject to the following conditions: // // The above copyright notice and this permission notice shall be included in all // copies or substantial portions of the Software. // // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE // SOFTWARE. #ifndef ESPStepperMotorServer_CLI_h #define ESPStepperMotorServer_CLI_h #define MAX_CLI_CMD_COUNTER 50 #define MAX_CLI_USER_CMD_COUNTER 5 #include #include //need this forward declaration here due to circular dependency (use in constructor/member variable) class ESPStepperMotorServer; struct commandDetailsStructure { String command; String shortCut; String description; bool hasParameters; }; class ESPStepperMotorServer_CLI { public: ESPStepperMotorServer_CLI(ESPStepperMotorServer *serverRef); ~ESPStepperMotorServer_CLI(); static void processSerialInput(void *parameter); void executeCommand(String cmd); void start(); void stop(); void registerNewUserCommand(commandDetailsStructure commandDetails, void (*f)(char *, char *)); int getValidStepperIdFromArg(char *arg); void getParameterValue(const char *args, const char *parameterNameToGetValueFor, char *result); void getUnitWithFallback(char *args, char *unit); private: void cmdHelp(char *cmd, char *args); void cmdEmergencyStop(char *cmd, char *args); void cmdRevokeEmergencyStop(char *cmd, char *args); void cmdGetPosition(char *cmd, char *args); void cmdGetCurrentVelocity(char *cmd, char *args); void cmdMoveBy(char *cmd, char *args); void cmdMoveTo(char *cmd, char *args); void cmdPrintConfig(char *cmd, char *args); void cmdRemoveSwitch(char *cmd, char *args); void cmdReboot(char *cmd, char *args); void cmdRemoveStepper(char *cmd, char *args); void cmdRemoveEncoder(char *cmd, char *args); void cmdStopServer(char *cmd, char *args); void cmdSwitchStatus(char *cmd, char *args); void cmdServerStatus(char *cmd, char *args); void cmdSetLogLevel(char *cmd, char *args); void cmdSaveConfiguration(char *cmd, char *args); void cmdSetApName(char *cmd, char *args); void cmdSetApPassword(char *cmd, char *args); #ifndef ESPStepperMotorServer_COMPILE_NO_WEB void cmdSetHttpPort(char *cmd, char *args); #endif void cmdSetSSID(char *cmd, char *args); void cmdSetWifiPassword(char *cmd, char *args); void registerCommands(); void registerNewCommand(commandDetailsStructure commandDetails, void (ESPStepperMotorServer_CLI::*f)(char *, char *)); void setMoveSpeedAccelHelper(ESP_FlexyStepper *flexyStepper, char *args); TaskHandle_t xHandle = NULL; ESPStepperMotorServer *serverRef; void (ESPStepperMotorServer_CLI::*command_functions[MAX_CLI_CMD_COUNTER + 1])(char *, char *); void (*user_command_functions[MAX_CLI_USER_CMD_COUNTER + 1])(char *, char *); //const char *command_details[MAX_CLI_CMD_COUNTER +1 ][4]; commandDetailsStructure allRegisteredCommands[MAX_CLI_CMD_COUNTER + 1]; commandDetailsStructure allRegisteredUserCommands[MAX_CLI_USER_CMD_COUNTER + 1]; unsigned int commandCounter = 0; unsigned int userCommandCounter = 0; const char *_CMD_PARAM_SEPARATOR = "="; const char *_PARAM_PARAM_SEPRATOR = "&"; const char *_PARAM_VALUE_SEPRATOR = ":"; }; #endif ================================================ FILE: src/ESPStepperMotorServer_Configuration.cpp ================================================ // ********************************************************* // * * // * Stepper Motor Server Configuration * // * * // * Copyright (c) Paul Kerspe, 2019 * // * * // ********************************************************** // this class repesents the complete configuration object and provide // helper functions to persist and load the configuration form the SPIFFS of the ESP // MIT License // // Copyright (c) 2019 Paul Kerspe // // Permission is hereby granted, free of charge, to any person obtaining a copy // of this software and associated documentation files (the "Software"), to deal // in the Software without restriction, including without limitation the rights // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell // copies of the Software, and to permit persons to whom the Software is furnished // to do so, subject to the following conditions: // // The above copyright notice and this permission notice shall be included in all // copies or substantial portions of the Software. // // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE // SOFTWARE. #include "ESPStepperMotorServer_Configuration.h" #include #define RESERVED_JSON_SIZE_ESPStepperMotorServer_Configuration 300 // // constructor for the stepper server configuration class // ESPStepperMotorServer_Configuration::ESPStepperMotorServer_Configuration(const char *configFilePath, bool isSPIFFSactive) { this->_configFilePath = configFilePath; this->_isSPIFFSactive = isSPIFFSactive; this->loadConfiguationFromSpiffs(); #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG if (ESPStepperMotorServer_Logger::getLogLevel() >= ESPServerLogLevel_DEBUG) { this->printCurrentConfigurationAsJsonToSerial(); } #endif } unsigned int ESPStepperMotorServer_Configuration::calculateRequiredJsonDocumentSizeForCurrentConfiguration() { unsigned int size = 0; size += RESERVED_JSON_SIZE_ESPStepperMotorServer_PositionSwitch * ESPServerMaxSwitches; size += RESERVED_JSON_SIZE_ESPStepperMotorServer_RotaryEncoder * ESPServerMaxRotaryEncoders; size += RESERVED_JSON_SIZE_ESPStepperMotorServer_StepperConfiguration * ESPServerMaxSteppers; size += RESERVED_JSON_SIZE_ESPStepperMotorServer_Configuration; return size; } void ESPStepperMotorServer_Configuration::printCurrentConfigurationAsJsonToSerial() { DynamicJsonDocument doc(this->calculateRequiredJsonDocumentSizeForCurrentConfiguration()); this->serializeServerConfiguration(doc, false); serializeJsonPretty(doc, Serial); Serial.println(); } String ESPStepperMotorServer_Configuration::getCurrentConfigurationAsJSONString(bool prettyPrint, bool includePasswords) { DynamicJsonDocument doc(this->calculateRequiredJsonDocumentSizeForCurrentConfiguration()); this->serializeServerConfiguration(doc, includePasswords); String output; if (prettyPrint) { serializeJsonPretty(doc, output); } else { serializeJson(doc, output); } return output; } void ESPStepperMotorServer_Configuration::serializeServerConfiguration(JsonDocument &doc, bool includePasswords) { // Set the values in the document doc[JSON_SECTION_NAME_SERVER_CONFIGURATION][JSON_PROPERTY_NAME_PORT_NUMBER] = this->serverPort; doc[JSON_SECTION_NAME_SERVER_CONFIGURATION][JSON_PROPERTY_NAME_WIFI_MODE] = this->wifiMode; doc[JSON_SECTION_NAME_SERVER_CONFIGURATION][JSON_PROPERTY_NAME_WIFI_SSID] = this->wifiSsid; doc[JSON_SECTION_NAME_SERVER_CONFIGURATION][JSON_PROPERTY_NAME_WIFI_PASSWORD] = (includePasswords) ? this->wifiPassword : "*****"; doc[JSON_SECTION_NAME_SERVER_CONFIGURATION][JSON_PROPERTY_NAME_WIFI_AP_NAME] = this->apName; doc[JSON_SECTION_NAME_SERVER_CONFIGURATION][JSON_PROPERTY_NAME_WIFI_AP_PASSWORD] = (includePasswords) ? this->apPassword : "*****"; doc[JSON_SECTION_NAME_SERVER_CONFIGURATION][JSON_PROPERTY_NAME_CPUCORE_FOR_MOTIONCONTROLLER_SERVICE] = this->motionControllerCpuCore; ESPStepperMotorServer_Logger::logInfof("Serializing config \n"); if (this->staticIP != 0) { ESPStepperMotorServer_Logger::logInfof("static ip = %s \n", this->staticIP.toString().c_str()); doc[JSON_SECTION_NAME_SERVER_CONFIGURATION][JSON_PROPERTY_NAME_WIFI_STATIC_IP_ADDRESS] = this->staticIP.toString(); } if (this->gatewayIP != 0) { ESPStepperMotorServer_Logger::logInfof("gateway ip = %s \n", this->gatewayIP.toString().c_str()); doc[JSON_SECTION_NAME_SERVER_CONFIGURATION][JSON_PROPERTY_NAME_WIFI_STATIC_IP_GATEWAY] = this->gatewayIP.toString(); } if (this->subnetMask != 0) { ESPStepperMotorServer_Logger::logInfof("subnetMask = %s \n", this->subnetMask.toString().c_str()); doc[JSON_SECTION_NAME_SERVER_CONFIGURATION][JSON_PROPERTY_NAME_WIFI_STATIC_IP_SUBNETMASK] = this->subnetMask.toString(); } if (this->dns1IP != 0) { ESPStepperMotorServer_Logger::logInfof("DNS1 ip = %s \n", this->dns1IP.toString().c_str()); doc[JSON_SECTION_NAME_SERVER_CONFIGURATION][JSON_PROPERTY_NAME_WIFI_STATIC_IP_DNS1] = this->dns1IP.toString(); } if (this->dns2IP != 0) { ESPStepperMotorServer_Logger::logInfof("DNS2 ip = %s \n", this->dns2IP.toString().c_str()); doc[JSON_SECTION_NAME_SERVER_CONFIGURATION][JSON_PROPERTY_NAME_WIFI_STATIC_IP_DNS2] = this->dns2IP.toString(); } // add all stepper configs JsonArray stepperConfigArray = doc.createNestedArray(JSON_SECTION_NAME_STEPPER_CONFIGURATIONS); for (byte stepperConfigIndex = 0; stepperConfigIndex < ESPServerMaxSteppers; stepperConfigIndex++) { ESPStepperMotorServer_StepperConfiguration *stepperConfig = this->getStepperConfiguration(stepperConfigIndex); if (stepperConfig) { JsonObject nestedStepperConfig = stepperConfigArray.createNestedObject(); nestedStepperConfig["id"] = stepperConfig->getId(); nestedStepperConfig["name"] = stepperConfig->getDisplayName(); nestedStepperConfig["stepPin"] = stepperConfig->getStepIoPin(); nestedStepperConfig["directionPin"] = stepperConfig->getDirectionIoPin(); nestedStepperConfig["stepsPerRev"] = stepperConfig->getStepsPerRev(); nestedStepperConfig["stepsPerMM"] = stepperConfig->getStepsPerMM(); nestedStepperConfig["microsteppingDivisor"] = stepperConfig->getMicrostepsPerStep(); nestedStepperConfig["rpmLimit"] = stepperConfig->getRpmLimit(); nestedStepperConfig["breakPin"] = stepperConfig->getBrakeIoPin(); nestedStepperConfig["breakPinActiveState"] = stepperConfig->getBrakePinActiveState(); nestedStepperConfig["breakEngageDelay"] = stepperConfig->getBrakeEngageDelayMs(); nestedStepperConfig["breakReleaseDelay"] = stepperConfig->getBrakeReleaseDelayMs(); } } // add all switch configs JsonArray switchConfigArray = doc.createNestedArray(JSON_SECTION_NAME_SWITCH_CONFIGURATIONS); for (byte switchConfigIndex = 0; switchConfigIndex < ESPServerMaxSwitches; switchConfigIndex++) { ESPStepperMotorServer_PositionSwitch *switchConfig = this->getSwitch(switchConfigIndex); if (switchConfig) { JsonObject nestedSwitchConfig = switchConfigArray.createNestedObject(); nestedSwitchConfig["id"] = switchConfig->getId(); nestedSwitchConfig["name"] = switchConfig->getPositionName(); nestedSwitchConfig["ioPin"] = switchConfig->getIoPinNumber(); nestedSwitchConfig["stepperIndex"] = switchConfig->getStepperIndex(); nestedSwitchConfig["switchType"] = switchConfig->getSwitchType(); nestedSwitchConfig["switchPosition"] = switchConfig->getSwitchPosition(); if (switchConfig->hasMacroActions()) { JsonArray macroActionsJsonArray = nestedSwitchConfig.createNestedArray(JSON_SECTION_NAME_SWITCH_CONFIGURATION_MACROACTIONS); switchConfig->serializeMacroActionsToJsonArray(macroActionsJsonArray); } } } // add all rotary encoder configs JsonArray encoderConfigArray = doc.createNestedArray(JSON_SECTION_NAME_ROTARY_ENCODER_CONFIGURATIONS); for (byte encoderConfigIndex = 0; encoderConfigIndex < ESPServerMaxRotaryEncoders; encoderConfigIndex++) { ESPStepperMotorServer_RotaryEncoder *encoderConfig = this->getRotaryEncoder(encoderConfigIndex); if (encoderConfig) { JsonObject nestedEncoderConfig = encoderConfigArray.createNestedObject(); nestedEncoderConfig["id"] = encoderConfig->getId(); nestedEncoderConfig["name"] = encoderConfig->getDisplayName(); nestedEncoderConfig["pinA"] = encoderConfig->getPinAIOPin(); nestedEncoderConfig["pinB"] = encoderConfig->getPinBIOPin(); nestedEncoderConfig["stepMultiplier"] = encoderConfig->getStepMultiplier(); nestedEncoderConfig["stepperIndex"] = encoderConfig->getStepperIndex(); } } } bool ESPStepperMotorServer_Configuration::saveCurrentConfiguationToSpiffs(String filename) { if (!this->_isSPIFFSactive) { ESPStepperMotorServer_Logger::logWarningf("Failed to save configuration file '%s' in SPIFFS, since SPIFFS is not mounted\n", filename.c_str()); return false; } if (filename == "") { filename = this->_configFilePath; } // assemble the json object first, to check if all goes well // Allocate a temporary JsonDocument DynamicJsonDocument doc(this->calculateRequiredJsonDocumentSizeForCurrentConfiguration()); this->serializeServerConfiguration(doc, true); // Delete existing file, otherwise the configuration is appended to the file LittleFS.remove(filename); // Open file for writing File file = LittleFS.open(filename, FILE_WRITE); if (!file) { ESPStepperMotorServer_Logger::logWarningf("Failed to create new configuration file '%s' in LittleFS\n", filename.c_str()); return false; } bool success = false; // Serialize JSON to file if (serializeJson(doc, file) == 0) { ESPStepperMotorServer_Logger::logWarningf("Failed to write new configuration to file '%s' in SPIFFS\n", filename.c_str()); } else { ESPStepperMotorServer_Logger::logInfof("New configuration file written in SPIFFS to '%s'\n", filename.c_str()); success = true; } // Close the file file.close(); return success; } bool ESPStepperMotorServer_Configuration::loadConfiguationFromSpiffs(String filename) { filename = (filename == "") ? this->_configFilePath : filename; filename = (filename.startsWith("/")) ? filename : "/" + filename; if (this->_isSPIFFSactive && LittleFS.exists(filename)) { ESPStepperMotorServer_Logger::logInfof("Loading configuration file %s from LittleFS\n", filename.c_str()); File configFile = LittleFS.open(filename, FILE_READ); DynamicJsonDocument doc(this->calculateRequiredJsonDocumentSizeForCurrentConfiguration()); this->serializeServerConfiguration(doc); // Deserialize the JSON document DeserializationError error = deserializeJson(doc, configFile); if (error) ESPStepperMotorServer_Logger::logWarningf("Failed to read configuration file %s. Will use fallback default configuration\n", filename.c_str()); #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG else { ESPStepperMotorServer_Logger::logDebug("File loaded and deserialized"); } #endif // Copy values from the JsonDocument to the Config // SERVER CONFIG this->serverPort = doc[JSON_SECTION_NAME_SERVER_CONFIGURATION][JSON_PROPERTY_NAME_PORT_NUMBER] | DEFAULT_SERVER_PORT; this->wifiMode = doc[JSON_SECTION_NAME_SERVER_CONFIGURATION][JSON_PROPERTY_NAME_WIFI_MODE] | DEFAULT_WIFI_MODE; JsonVariant value = doc[JSON_SECTION_NAME_SERVER_CONFIGURATION][JSON_PROPERTY_NAME_WIFI_AP_NAME]; this->apName = (value) ? value.as() : "ESP-StepperMotor-Server"; value = doc[JSON_SECTION_NAME_SERVER_CONFIGURATION][JSON_PROPERTY_NAME_WIFI_AP_PASSWORD]; this->apPassword = (value) ? value.as() : "Aa123456"; value = doc[JSON_SECTION_NAME_SERVER_CONFIGURATION][JSON_PROPERTY_NAME_CPUCORE_FOR_MOTIONCONTROLLER_SERVICE]; this->motionControllerCpuCore = (value) ? value.as() : 0; this->wifiSsid = doc[JSON_SECTION_NAME_SERVER_CONFIGURATION][JSON_PROPERTY_NAME_WIFI_SSID].as(); this->wifiPassword = doc[JSON_SECTION_NAME_SERVER_CONFIGURATION][JSON_PROPERTY_NAME_WIFI_PASSWORD].as(); // read static IP settings if any if (doc[JSON_SECTION_NAME_SERVER_CONFIGURATION].containsKey(JSON_PROPERTY_NAME_WIFI_STATIC_IP_ADDRESS)) { this->staticIP.fromString(doc[JSON_SECTION_NAME_SERVER_CONFIGURATION][JSON_PROPERTY_NAME_WIFI_STATIC_IP_ADDRESS].as()); } if (doc[JSON_SECTION_NAME_SERVER_CONFIGURATION].containsKey(JSON_PROPERTY_NAME_WIFI_STATIC_IP_GATEWAY)) { this->gatewayIP.fromString(doc[JSON_SECTION_NAME_SERVER_CONFIGURATION][JSON_PROPERTY_NAME_WIFI_STATIC_IP_GATEWAY].as()); } if (doc[JSON_SECTION_NAME_SERVER_CONFIGURATION].containsKey(JSON_PROPERTY_NAME_WIFI_STATIC_IP_SUBNETMASK)) { this->subnetMask.fromString(doc[JSON_SECTION_NAME_SERVER_CONFIGURATION][JSON_PROPERTY_NAME_WIFI_STATIC_IP_SUBNETMASK].as()); } if (doc[JSON_SECTION_NAME_SERVER_CONFIGURATION].containsKey(JSON_PROPERTY_NAME_WIFI_STATIC_IP_DNS1)) { this->dns1IP.fromString(doc[JSON_SECTION_NAME_SERVER_CONFIGURATION][JSON_PROPERTY_NAME_WIFI_STATIC_IP_DNS1].as()); } if (doc[JSON_SECTION_NAME_SERVER_CONFIGURATION].containsKey(JSON_PROPERTY_NAME_WIFI_STATIC_IP_DNS2)) { this->dns2IP.fromString(doc[JSON_SECTION_NAME_SERVER_CONFIGURATION][JSON_PROPERTY_NAME_WIFI_STATIC_IP_DNS2].as()); } // STEPPER CONFIG JsonArray configs = doc[JSON_SECTION_NAME_STEPPER_CONFIGURATIONS].as(); byte configCounter = 0; if (!configs) { ESPStepperMotorServer_Logger::logInfo("No stepper configuration present in config file"); } else { for (JsonVariant stepperConfigEntry : configs) { const char *value = stepperConfigEntry["name"].as(); ESPStepperMotorServer_StepperConfiguration *stepperConfig = new ESPStepperMotorServer_StepperConfiguration( (stepperConfigEntry["stepPin"] | 255), (stepperConfigEntry["directionPin"] | 255), ((value) ? value : "undefined"), (stepperConfigEntry["stepsPerRev"] | 200), (stepperConfigEntry["stepsPerMM"] | 100), (stepperConfigEntry["microsteppingDivisor"] | ESPSMS_MICROSTEPS_OFF), (stepperConfigEntry["rpmLimit"] | 1000)); //set break settings stepperConfig->setBrakeIoPin(stepperConfigEntry["breakPin"] | stepperConfig->ESPServerStepperUnsetIoPinNumber, stepperConfigEntry["breakPinActiveState"] | 1); stepperConfig->setBrakeEngageDelayMs(stepperConfigEntry["breakEngageDelay"] | 0); stepperConfig->setBrakeReleaseDelayMs(stepperConfigEntry["breakReleaseDelay"] | -1); if (stepperConfigEntry["id"]) { this->setStepperConfiguration(stepperConfig, stepperConfigEntry["id"]); } else { this->addStepperConfiguration(stepperConfig); } configCounter++; } ESPStepperMotorServer_Logger::logInfof("%i stepper configuration entr%s loaded from config file\n", configCounter, (configCounter == 1) ? "y" : "ies"); } // SWITCH CONFIG configCounter = 0; configs = doc[JSON_SECTION_NAME_SWITCH_CONFIGURATIONS].as(); if (!configs) { ESPStepperMotorServer_Logger::logInfo("No switch configuration present in config file"); } else { for (JsonVariant switchConfigEntry : configs) { const char *value = switchConfigEntry["name"].as(); ESPStepperMotorServer_PositionSwitch *switchConfig = new ESPStepperMotorServer_PositionSwitch( (switchConfigEntry["ioPin"] | 255), (switchConfigEntry["stepperIndex"] | 255), (switchConfigEntry["switchType"] | 255), ((value) ? value : "undefined"), (switchConfigEntry["switchPosition"] | 0)); //check for macro actions if (switchConfigEntry[JSON_SECTION_NAME_SWITCH_CONFIGURATION_MACROACTIONS]) { JsonArray macroActionsJsonArray = switchConfigEntry[JSON_SECTION_NAME_SWITCH_CONFIGURATION_MACROACTIONS].as(); if (macroActionsJsonArray) { for (JsonVariant macroActionJson : macroActionsJsonArray) { switchConfig->addMacroAction(ESPStepperMotorServer_MacroAction::fromJsonObject(macroActionJson)); } } } if (switchConfigEntry["id"]) { this->setSwitch(switchConfig, switchConfigEntry["id"]); } else { this->addSwitch(switchConfig); } configCounter++; } ESPStepperMotorServer_Logger::logInfof("%i switch configuration entr%s loaded from config file\n", configCounter, (configCounter == 1) ? "y" : "ies"); } // ENCODER CONFIG configCounter = 0; configs = doc[JSON_SECTION_NAME_ROTARY_ENCODER_CONFIGURATIONS].as(); if (!configs) { ESPStepperMotorServer_Logger::logInfo("No rotary encoder configuration present in config file"); } else { for (JsonVariant encoderConfigEntry : configs) { const char *value = encoderConfigEntry["name"].as(); //char pinA, char pinB, String displayName, int stepMultiplier, byte stepperIndex ESPStepperMotorServer_RotaryEncoder *encoderConfig = new ESPStepperMotorServer_RotaryEncoder( (encoderConfigEntry["pinA"] | 255), (encoderConfigEntry["pinB"] | 255), ((value) ? value : "undefined"), (encoderConfigEntry["stepMultiplier"] | 255), (encoderConfigEntry["stepperIndex"] | 255)); if (encoderConfigEntry["id"]) { this->setRotaryEncoder(encoderConfig, encoderConfigEntry["id"]); } else { this->addRotaryEncoder(encoderConfig); } configCounter++; } ESPStepperMotorServer_Logger::logInfof("%i rotary encoder configuration entr%s loaded from config file\n", configCounter, (configCounter == 1) ? "y" : "ies"); } // Close the file configFile.close(); return true; } else { ESPStepperMotorServer_Logger::logWarningf("Failed to load configuration file from LittleFS. File %s not found or LittleFS is not enabled/mounted\n", filename.c_str()); return false; } } byte ESPStepperMotorServer_Configuration::addStepperConfiguration(ESPStepperMotorServer_StepperConfiguration *stepperConfig) { //find first index that is not NULL and use as id byte id = 0; for (id = 0; id < ESPServerMaxSteppers; id++) { if (this->configuredSteppers[id] == NULL) { stepperConfig->setId(id); this->configuredSteppers[id] = stepperConfig; this->updateConfiguredFlexyStepperCache(); return id; } } ESPStepperMotorServer_Logger::logWarningf("The maximum amount of stepper configurations (%i) that can be configured has been reached, no more stepper configs can be added\n", ESPServerMaxSteppers); return 255; } byte ESPStepperMotorServer_Configuration::addSwitch(ESPStepperMotorServer_PositionSwitch *positionSwitch) { //find first index that is not NULL and use as id byte id = 0; for (id = 0; id < ESPServerMaxSwitches; id++) { if (this->allConfiguredSwitches[id] == NULL) { positionSwitch->setId(id); this->allConfiguredSwitches[id] = positionSwitch; this->updateSwitchCaches(); return id; } } ESPStepperMotorServer_Logger::logWarningf("The maximum amount of switches (%i) that can be configured has been reached, no more switches can be added\n", ESPServerMaxSwitches); return 255; } byte ESPStepperMotorServer_Configuration::addRotaryEncoder(ESPStepperMotorServer_RotaryEncoder *encoder) { //find first index that is not NULL and use as id byte id = 0; for (id = 0; id < ESPServerMaxRotaryEncoders; id++) { if (this->configuredRotaryEncoders[id] == NULL) { encoder->setId(id); this->configuredRotaryEncoders[id] = encoder; return id; } } ESPStepperMotorServer_Logger::logWarningf("The maximum amount of rotary encoders (%i) that can be configured has been reached, no more encoders can be added\n", ESPServerMaxRotaryEncoders); return 255; } void ESPStepperMotorServer_Configuration::setStepperConfiguration(ESPStepperMotorServer_StepperConfiguration *stepperConfig, byte id) { if (id >= ESPServerMaxSteppers) { ESPStepperMotorServer_Logger::logWarningf("The given stepper id/index (%i) exceeds the allowed max amount of %i. Stepper config will not be set\n", id, ESPServerMaxSteppers); } else { stepperConfig->setId(id); this->configuredSteppers[id] = stepperConfig; } this->updateConfiguredFlexyStepperCache(); } void ESPStepperMotorServer_Configuration::setSwitch(ESPStepperMotorServer_PositionSwitch *positionSwitch, byte id) { if (id >= ESPServerMaxSwitches) { ESPStepperMotorServer_Logger::logWarningf("The given switch id/index (%i) exceeds the allowed max amount of %i. Switch config will not be set\n", id, ESPServerMaxSteppers); } else { positionSwitch->setId(id); this->allConfiguredSwitches[id] = positionSwitch; this->updateSwitchCaches(); } } void ESPStepperMotorServer_Configuration::setRotaryEncoder(ESPStepperMotorServer_RotaryEncoder *encoder, byte id) { if (id >= ESPServerMaxRotaryEncoders) { ESPStepperMotorServer_Logger::logWarningf("The given rotray encoder id/index (%i) exceeds the allowed max amount of %i. Rotray encoder config will not be set\n", id, ESPServerMaxSteppers); } else { encoder->setId(id); this->configuredRotaryEncoders[id] = encoder; } } ESPStepperMotorServer_StepperConfiguration *ESPStepperMotorServer_Configuration::getStepperConfiguration(unsigned char id) { if (id >= ESPServerMaxSteppers) { ESPStepperMotorServer_Logger::logWarningf("Invalid stepper config requested with id %i. Will retun NULL\n", id); return NULL; } return this->configuredSteppers[id]; } void ESPStepperMotorServer_Configuration::updateConfiguredFlexyStepperCache() { byte flexyStepperCounter = 0; ESPStepperMotorServer_StepperConfiguration *stepper; //clear list first for (byte i = 0; i < ESPServerMaxSteppers; i++) { //TODO: check if this delete call is appropriate, currently it casues kernel panic //delete (this->configuredFlexySteppers[i]); this->configuredFlexySteppers[i] = NULL; } for (byte i = 0; i < ESPServerMaxSteppers; i++) { stepper = this->getStepperConfiguration(i); if (stepper) { this->configuredFlexySteppers[flexyStepperCounter] = stepper->getFlexyStepper(); flexyStepperCounter++; } } } ESP_FlexyStepper **ESPStepperMotorServer_Configuration::getConfiguredFlexySteppers() { return this->configuredFlexySteppers; } ESPStepperMotorServer_PositionSwitch *ESPStepperMotorServer_Configuration::getSwitch(byte id) { if (id < 0 || id > ESPServerMaxSwitches - 1) { ESPStepperMotorServer_Logger::logWarningf("Invalid switch config requested with id %i. Will retun NULL\n", id); return NULL; } return this->allConfiguredSwitches[id]; } ESPStepperMotorServer_PositionSwitch *ESPStepperMotorServer_Configuration::getFirstConfiguredLimitSwitchForStepper(unsigned char steperConfigId) { for (byte i = 0; i < ESPServerMaxSwitches; i++) { ESPStepperMotorServer_PositionSwitch *positionSwitch = this->configuredLimitSwitches[i]; if (positionSwitch != NULL && positionSwitch->getStepperIndex() == steperConfigId) { return positionSwitch; } } return NULL; } ESPStepperMotorServer_RotaryEncoder *ESPStepperMotorServer_Configuration::getRotaryEncoder(unsigned char id) { if (id >= ESPServerMaxRotaryEncoders) { ESPStepperMotorServer_Logger::logWarningf("Invalid rotary encoder config requested with id %i. Will retun NULL\n", id); return NULL; } return this->configuredRotaryEncoders[id]; } void ESPStepperMotorServer_Configuration::removeStepperConfiguration(byte id) { //check if any switches are connected to this stepper and delete those for (byte switchIndex = 0; switchIndex < ESPServerMaxSwitches; switchIndex++) { ESPStepperMotorServer_PositionSwitch *switchConfig = this->getSwitch(switchIndex); if (switchConfig && switchConfig->getStepperIndex() == id) { #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG ESPStepperMotorServer_Logger::logDebugf("Found switch configuration (id=%i) that is linked to stepper config (id=%i) to be deleted. Will delete switch config as well\n", switchConfig->getId(), id); #endif this->removeSwitch(switchIndex); } } //check if any switches are connected to this stepper and delete those for (byte encoderIndex = 0; encoderIndex < ESPServerMaxRotaryEncoders; encoderIndex++) { ESPStepperMotorServer_RotaryEncoder *encoderConfig = this->getRotaryEncoder(encoderIndex); if (encoderConfig && encoderConfig->getStepperIndex() == id) { #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG ESPStepperMotorServer_Logger::logDebugf("Found encoder configuration (id=%i) that is linked to stepper config (id=%i) to be deleted. Will delete encoder config as well\n", encoderConfig->getId(), id); #endif this->removeRotaryEncoder(encoderIndex); } } //finally delete the stepper config itself //TODO: check if this delete call is appropriate, currently it casues kernel panic //delete (this->configuredSteppers[id]); this->configuredSteppers[id] = NULL; this->updateConfiguredFlexyStepperCache(); } void ESPStepperMotorServer_Configuration::removeSwitch(byte id) { //TODO: check if this delete call is appropriate, currently it casues kernel panic //delete (this->allConfiguredSwitches[id]); this->allConfiguredSwitches[id] = NULL; this->updateSwitchCaches(); } void ESPStepperMotorServer_Configuration::updateSwitchCaches() { //reset all caches first for (byte i = 0; i < ESPServerMaxSwitches; i++) { //TODO: check if this is appropriate, currently it causes kernel panic //delete (this->configuredEmergencySwitches[i]); this->configuredEmergencySwitches[i] = NULL; //TODO: check if this delete call is appropriate, currently it casues kernel panic //delete (this->configuredLimitSwitches[i]); this->configuredLimitSwitches[i] = NULL; this->allSwitchIoPins[i] = (signed char)-1; } //now rebuild the caches byte emergencySwitchCacheIndex = 0; byte limitSwitchCacheIndex = 0; for (byte i = 0; i < ESPServerMaxSwitches; i++) { if (this->allConfiguredSwitches[i]) { this->allSwitchIoPins[i] = this->allConfiguredSwitches[i]->getIoPinNumber(); if (this->allConfiguredSwitches[i]->isEmergencySwitch()) { this->configuredEmergencySwitches[emergencySwitchCacheIndex] = this->allConfiguredSwitches[i]; emergencySwitchCacheIndex++; } else if (this->allConfiguredSwitches[i]->isLimitSwitch()) { this->configuredLimitSwitches[limitSwitchCacheIndex] = this->allConfiguredSwitches[i]; limitSwitchCacheIndex++; } } } } void ESPStepperMotorServer_Configuration::removeRotaryEncoder(byte id) { //TODO: check if this delete call is appropriate, currently it casues kernel panic //delete (this->configuredRotaryEncoders[id]); this->configuredRotaryEncoders[id] = NULL; } ================================================ FILE: src/ESPStepperMotorServer_Configuration.h ================================================ // ****************************************************************** // * * // * Header file for ESPStepperMotorServer_Configuration.cpp * // * * // * Copyright (c) Paul Kerspe, 2019 * // * * // ****************************************************************** // this class repesents the complete configuration object and provide // helper functions to persist and load the configuration form the SPIFFS of the ESP // MIT License // // Copyright (c) 2019 Paul Kerspe // // Permission is hereby granted, free of charge, to any person obtaining a copy // of this software and associated documentation files (the "Software"), to deal // in the Software without restriction, including without limitation the rights // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell // copies of the Software, and to permit persons to whom the Software is furnished // to do so, subject to the following conditions: // // The above copyright notice and this permission notice shall be included in all // copies or substantial portions of the Software. // // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE // SOFTWARE. #ifndef ESPStepperMotorServer_Configuration_h #define ESPStepperMotorServer_Configuration_h #include #include #include #include #include #include #include #include // TODO: get IO pin configration rules implemented and helper to provide information about which pins to use and which not // https://randomnerdtutorials.com/esp32-pinout-reference-gpios/ // Input only pins // GPIOs 34 to 39 are GPIs – input only pins. These pins don’t have internal pull-ups or pull-down resistors. They can’t be used as outputs, so use these pins only as inputs: // GPIO 34, GPIO 35, GPIO 36, GPIO 39 // GPIO 12 boot fail if pulled high, better not use as active low #define DEFAULT_SERVER_PORT 80 #define DEFAULT_WIFI_MODE 1 class ESPStepperMotorServer_PositionSwitch; // // the ESPStepperMotorServer_Configuration class class ESPStepperMotorServer_Configuration { friend class ESPStepperMotorServer; friend class ESPStepperMotorServer_RestAPI; public: ESPStepperMotorServer_Configuration(const char *configFilePath, bool isSPIFFSactive); String getCurrentConfigurationAsJSONString(bool prettyPrint = true, bool includePasswords = false); unsigned int calculateRequiredJsonDocumentSizeForCurrentConfiguration(); void printCurrentConfigurationAsJsonToSerial(); bool saveCurrentConfiguationToSpiffs(String filename = ""); bool loadConfiguationFromSpiffs(String filename = ""); void serializeServerConfiguration(JsonDocument &doc, bool includePasswords = false); byte addStepperConfiguration(ESPStepperMotorServer_StepperConfiguration *stepperConfig); byte addSwitch(ESPStepperMotorServer_PositionSwitch *positionSwitch); byte addRotaryEncoder(ESPStepperMotorServer_RotaryEncoder *encoder); void setStepperConfiguration(ESPStepperMotorServer_StepperConfiguration *stepperConfig, byte id); void setSwitch(ESPStepperMotorServer_PositionSwitch *positionSwitch, byte id); void setRotaryEncoder(ESPStepperMotorServer_RotaryEncoder *encoder, byte id); void removeStepperConfiguration(byte id); void removeSwitch(byte id); void removeRotaryEncoder(byte id); ESPStepperMotorServer_StepperConfiguration *getStepperConfiguration(unsigned char id); ESPStepperMotorServer_PositionSwitch *getSwitch(byte id); ESPStepperMotorServer_PositionSwitch *getFirstConfiguredLimitSwitchForStepper(unsigned char id); ESPStepperMotorServer_RotaryEncoder *getRotaryEncoder(unsigned char id); ESP_FlexyStepper **getConfiguredFlexySteppers(); // a cache containing all IO pins that are used by switches. The indexes matches the indexes in the configuredSwitches (=switch ID) // -1 is used to indicate an emtpy array slot signed char allSwitchIoPins[ESPServerMaxSwitches]; int serverPort = DEFAULT_SERVER_PORT; int wifiMode = 1; const char *apName = "ESPStepperMotorServer"; const char *apPassword = "Aa123456"; const char *wifiSsid = "undefined"; const char *wifiPassword = "undefined"; int motionControllerCpuCore = 0; IPAddress staticIP; IPAddress gatewayIP; IPAddress subnetMask; IPAddress dns1IP; IPAddress dns2IP; //this "cache" should not be private since we need to use it in the ISRs and any getter to retrieve it would slow down processing ESPStepperMotorServer_PositionSwitch *configuredEmergencySwitches[ESPServerMaxSwitches] = {NULL}; private: // // private member variables // bool isCurrentConfigurationSaved = false; const char *_configFilePath; bool _isSPIFFSactive = false; /**** the follwoing variables represent the in-memory configuration settings *******/ // an array to hold all configured stepper configurations ESPStepperMotorServer_StepperConfiguration *configuredSteppers[ESPServerMaxSteppers] = {NULL}; // this is a shortcut/cache for all configured flexy stepper instances, yet it will not have the same indexes as the configuredSteppers, // but solely an array that is filled from the beginnnig without emtpy slots. // it is used to have a quick access to configured flexy steppers in time critical functions void updateConfiguredFlexyStepperCache(void); ESP_FlexyStepper *configuredFlexySteppers[ESPServerMaxSteppers] = {NULL}; // an array to hold all configured switches ESPStepperMotorServer_PositionSwitch *allConfiguredSwitches[ESPServerMaxSwitches] = {NULL}; // update the caches for emergency and limit switches void updateSwitchCaches(); ESPStepperMotorServer_PositionSwitch *configuredLimitSwitches[ESPServerMaxSwitches] = {NULL}; // an array to hold all configured rotary encoders ESPStepperMotorServer_RotaryEncoder *configuredRotaryEncoders[ESPServerMaxRotaryEncoders] = {NULL}; ///////////////////////////////////////////////////// // CONSTANTS FOR JSON CONFIGURATION PROPERTY NAMES // ///////////////////////////////////////////////////// // GENERAL SERVER CONFIGURATION // const char *JSON_SECTION_NAME_SERVER_CONFIGURATION = "serverConfiguration"; const char *JSON_PROPERTY_NAME_PORT_NUMBER = "port"; const char *JSON_PROPERTY_NAME_WIFI_MODE = "wififMode"; //allowed values are 0 (wifi off = ESPServerWifiModeDisabled),1 (AP mode = ESPServerWifiModeAccessPoint) and 2 (client mode = ESPServerWifiModeClient) const char *JSON_PROPERTY_NAME_WIFI_SSID = "wifiSsid"; const char *JSON_PROPERTY_NAME_WIFI_PASSWORD = "wifiPassword"; const char *JSON_PROPERTY_NAME_WIFI_AP_NAME = "apName"; const char *JSON_PROPERTY_NAME_WIFI_AP_PASSWORD = "apPassword"; const char *JSON_PROPERTY_NAME_CPUCORE_FOR_MOTIONCONTROLLER_SERVICE = "motionControllerCpuCore"; //for static IP settings const char *JSON_PROPERTY_NAME_WIFI_STATIC_IP_ADDRESS = "staticIP"; const char *JSON_PROPERTY_NAME_WIFI_STATIC_IP_GATEWAY = "gatewayIP"; const char *JSON_PROPERTY_NAME_WIFI_STATIC_IP_SUBNETMASK = "subnetMask"; const char *JSON_PROPERTY_NAME_WIFI_STATIC_IP_DNS1 = "dns1IP"; const char *JSON_PROPERTY_NAME_WIFI_STATIC_IP_DNS2 = "dns2IP"; // STEPPER SPECIFIC CONFIGURATION // const char *JSON_SECTION_NAME_STEPPER_CONFIGURATIONS = "stepperConfigurations"; // SWITCH SPECIFIC CONFIGURATION // const char *JSON_SECTION_NAME_SWITCH_CONFIGURATIONS = "switchConfigurations"; const char *JSON_SECTION_NAME_SWITCH_CONFIGURATION_MACROACTIONS = "macroActions"; // ROTARY ENCODER SPECIFIC CONFIGURATION // const char *JSON_SECTION_NAME_ROTARY_ENCODER_CONFIGURATIONS = "rotaryEncoderConfigurations"; }; #endif ================================================ FILE: src/ESPStepperMotorServer_Logger.cpp ================================================ // ******************************************************************* // * * // * ESP8266 and ESP32 Stepper Motor Server - Logging class * // * Copyright (c) Paul Kerspe, 2019 * // * * // ******************************************************************* // // MIT License // // Copyright (c) 2019 Paul Kerspe // // Permission is hereby granted, free of charge, to any person obtaining a copy // of this software and associated documentation files (the "Software"), to deal // in the Software without restriction, including without limitation the rights // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell // copies of the Software, and to permit persons to whom the Software is furnished // to do so, subject to the following conditions: // // The above copyright notice and this permission notice shall be included in all // copies or substantial portions of the Software. // // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE // SOFTWARE. // #include byte ESPStepperMotorServer_Logger::_logLevel = ESPServerLogLevel_INFO; bool ESPStepperMotorServer_Logger::_isDebugLevelSet = false; const char *LEVEL_STRING_ALL = "ALL"; const char *LEVEL_STRING_DEBUG = "DEBUG"; const char *LEVEL_STRING_INFO = "INFO"; const char *LEVEL_STRING_WARNING = "WARNING"; ESPStepperMotorServer_Logger::ESPStepperMotorServer_Logger(String loggerName) { this->_loggerName = loggerName; } ESPStepperMotorServer_Logger::ESPStepperMotorServer_Logger() { this->_loggerName = "root"; } void ESPStepperMotorServer_Logger::printBinaryWithLeadingZeros(char *result, byte var) { int charIndex = 0; for (byte test = 0x80; test; test >>= 1) { result[charIndex] = (var & test) ? '1' : '0'; charIndex++; // Serial.write(var & test ? '1' : '0'); } result[charIndex] = '\0'; } void ESPStepperMotorServer_Logger::setLogLevel(byte logLevel) { ESPStepperMotorServer_Logger::_isDebugLevelSet = false; const char *msgTemplate = "Setting log level to %s\n"; switch (logLevel) { case ESPServerLogLevel_ALL: ESPStepperMotorServer_Logger::logInfof(msgTemplate, LEVEL_STRING_ALL); ESPStepperMotorServer_Logger::_isDebugLevelSet = true; break; case ESPServerLogLevel_DEBUG: ESPStepperMotorServer_Logger::logInfof(msgTemplate, LEVEL_STRING_DEBUG); ESPStepperMotorServer_Logger::_isDebugLevelSet = true; break; case ESPServerLogLevel_INFO: ESPStepperMotorServer_Logger::logInfof(msgTemplate, LEVEL_STRING_INFO); break; case ESPServerLogLevel_WARNING: ESPStepperMotorServer_Logger::logInfof(msgTemplate, LEVEL_STRING_WARNING); break; default: ESPStepperMotorServer_Logger::logWarning("Invalid log level given, log level will be set to info"); ESPStepperMotorServer_Logger::_logLevel = ESPServerLogLevel_INFO; return; } ESPStepperMotorServer_Logger::_logLevel = logLevel; } byte ESPStepperMotorServer_Logger::getLogLevel() { return ESPStepperMotorServer_Logger::_logLevel; } void ESPStepperMotorServer_Logger::logf(const char *level, const char *format, va_list args) { char buf[1000]; vsnprintf(buf, sizeof(buf), format, args); ESPStepperMotorServer_Logger::log(level, buf, false, false); } void ESPStepperMotorServer_Logger::log(const char *level, const char *msg, boolean newLine, boolean ommitLogLevel) { if (!ommitLogLevel) { Serial.printf("[%s] ", level); } if (newLine == true) { Serial.println(msg); } else { Serial.print(msg); } } bool ESPStepperMotorServer_Logger::isDebugEnabled() { return ESPStepperMotorServer_Logger::_isDebugLevelSet; } #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG void ESPStepperMotorServer_Logger::logDebug(const char *msg, boolean newLine, boolean ommitLogLevel) { if (ESPStepperMotorServer_Logger::_isDebugLevelSet) { ESPStepperMotorServer_Logger::log(LEVEL_STRING_DEBUG, msg, newLine, ommitLogLevel); } } void ESPStepperMotorServer_Logger::logDebugf(const char *format, ...) { if (ESPStepperMotorServer_Logger::_isDebugLevelSet) { va_list _argumentList; va_start(_argumentList, format); ESPStepperMotorServer_Logger::logf(LEVEL_STRING_DEBUG, format, _argumentList); va_end(_argumentList); } } void ESPStepperMotorServer_Logger::logDebug(String msg, boolean newLine, boolean ommitLogLevel) { if (ESPStepperMotorServer_Logger::_isDebugLevelSet) { ESPStepperMotorServer_Logger::logDebug(msg.c_str(), newLine, ommitLogLevel); } } #endif void ESPStepperMotorServer_Logger::logInfo(const char *msg, boolean newLine, boolean ommitLogLevel) { if (getLogLevel() >= ESPServerLogLevel_INFO) { ESPStepperMotorServer_Logger::log(LEVEL_STRING_INFO, msg, newLine, ommitLogLevel); } } void ESPStepperMotorServer_Logger::logInfof(const char *format, ...) { if (getLogLevel() >= ESPServerLogLevel_INFO) { va_list args; va_start(args, format); ESPStepperMotorServer_Logger::logf(LEVEL_STRING_INFO, format, args); va_end(args); } } void ESPStepperMotorServer_Logger::logWarning(const char *msg, boolean newLine, boolean ommitLogLevel) { ESPStepperMotorServer_Logger::log(LEVEL_STRING_WARNING, msg, newLine, ommitLogLevel); } void ESPStepperMotorServer_Logger::logWarningf(const char *format, ...) { va_list args; va_start(args, format); ESPStepperMotorServer_Logger::logf(LEVEL_STRING_WARNING, format, args); va_end(args); } ================================================ FILE: src/ESPStepperMotorServer_Logger.h ================================================ // ****************************************************************** // * * // * Header file for ESPStepperMotorServer_Logger.cpp * // * * // * Copyright (c) Paul Kerspe, 2019 * // * * // ****************************************************************** // MIT License // // Copyright (c) 2019 Paul Kerspe // // Permission is hereby granted, free of charge, to any person obtaining a copy // of this software and associated documentation files (the "Software"), to deal // in the Software without restriction, including without limitation the rights // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell // copies of the Software, and to permit persons to whom the Software is furnished // to do so, subject to the following conditions: // // The above copyright notice and this permission notice shall be included in all // copies or substantial portions of the Software. // // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE // SOFTWARE. #ifndef ESPStepperMotorServer_Logger_h #define ESPStepperMotorServer_Logger_h #include #define ESPServerLogLevel_ALL 4 #define ESPServerLogLevel_DEBUG 3 #define ESPServerLogLevel_INFO 2 #define ESPServerLogLevel_WARNING 1 // // the ESPStepperMotorServer_Logger class class ESPStepperMotorServer_Logger { public: ESPStepperMotorServer_Logger(); ESPStepperMotorServer_Logger(String logName); static void setLogLevel(byte); static byte getLogLevel(void); static void logDebug(const char *msg, boolean newLine = true, boolean ommitLogLevel = false); static void logDebugf(const char *format, ...); static void logDebug(String msg, boolean newLine = true, boolean ommitLogLevel = false); static void logInfo(const char *msg, boolean newLine = true, boolean ommitLogLevel = false); static void logInfof(const char *format, ...); static void logWarning(const char *msg, boolean newLine = true, boolean ommitLogLevel = false); static void logWarningf(const char *format, ...); static bool isDebugEnabled(); private: static void log(const char *level, const char *msg, boolean newLine, boolean ommitLogLevel); static void printBinaryWithLeadingZeros(char *result, byte var); static void logf(const char *level, const char *format, va_list args); static byte _logLevel; static bool _isDebugLevelSet; String _loggerName; }; #endif ================================================ FILE: src/ESPStepperMotorServer_MacroAction.cpp ================================================ #include #include "ESPStepperMotorServer.h" ESPStepperMotorServer_MacroAction::ESPStepperMotorServer_MacroAction(MacroActionType actionType, int val1, long val2) { this->actionType = actionType; this->val1 = val1; this->val2 = val2; } bool ESPStepperMotorServer_MacroAction::execute(ESPStepperMotorServer *serverRef) { Serial.println("Execute called for MacroAction"); switch (this->actionType) { case moveBy: { ESPStepperMotorServer_StepperConfiguration *stepper = serverRef->getCurrentServerConfiguration()->getStepperConfiguration(this->val1); if (stepper && stepper->getFlexyStepper()) { stepper->getFlexyStepper()->moveRelativeInSteps(this->val2); } break; } case MacroActionType::moveTo: { ESPStepperMotorServer_StepperConfiguration *stepper = serverRef->getCurrentServerConfiguration()->getStepperConfiguration(this->val1); if (stepper && stepper->getFlexyStepper()) { stepper->getFlexyStepper()->setTargetPositionInSteps(this->val2); } break; } case MacroActionType::releaseEmergencyStop: { serverRef->revokeEmergencyStop(); break; } case MacroActionType::triggerEmergencyStop: { serverRef->performEmergencyStop(); break; } case MacroActionType::setAcceleration: { ESPStepperMotorServer_StepperConfiguration *stepper = serverRef->getCurrentServerConfiguration()->getStepperConfiguration(this->val1); if (stepper && stepper->getFlexyStepper()) { stepper->getFlexyStepper()->setAccelerationInStepsPerSecondPerSecond((float)this->val2); } break; } case MacroActionType::setDeceleration: { ESPStepperMotorServer_StepperConfiguration *stepper = serverRef->getCurrentServerConfiguration()->getStepperConfiguration(this->val1); if (stepper && stepper->getFlexyStepper()) { stepper->getFlexyStepper()->setDecelerationInStepsPerSecondPerSecond((float)this->val2); } break; } case MacroActionType::setHome: { ESPStepperMotorServer_StepperConfiguration *stepper = serverRef->getCurrentServerConfiguration()->getStepperConfiguration(this->val1); if (stepper && stepper->getFlexyStepper()) { stepper->getFlexyStepper()->setCurrentPositionAsHomeAndStop(); } break; } case MacroActionType::setLimitA: { ESPStepperMotorServer_StepperConfiguration *stepper = serverRef->getCurrentServerConfiguration()->getStepperConfiguration(this->val1); if (stepper && stepper->getFlexyStepper()) { stepper->getFlexyStepper()->setLimitSwitchActive(ESP_FlexyStepper::LIMIT_SWITCH_BEGIN); } break; } case MacroActionType::setLimitB: { ESPStepperMotorServer_StepperConfiguration *stepper = serverRef->getCurrentServerConfiguration()->getStepperConfiguration(this->val1); if (stepper && stepper->getFlexyStepper()) { stepper->getFlexyStepper()->setLimitSwitchActive(ESP_FlexyStepper::LIMIT_SWITCH_END); } break; } case MacroActionType::setSpeed: { ESPStepperMotorServer_StepperConfiguration *stepper = serverRef->getCurrentServerConfiguration()->getStepperConfiguration(this->val1); if (stepper && stepper->getFlexyStepper()) { stepper->getFlexyStepper()->setSpeedInStepsPerSecond(this->val2); } break; } case MacroActionType::setOutputHigh: digitalWrite(this->val1, HIGH); break; case MacroActionType::setOutputLow: digitalWrite(this->val1, LOW); break; default: break; } return true; } void ESPStepperMotorServer_MacroAction::addSerializedInstanceToJsonArray(JsonArray jsonArray) { JsonObject nestedMacroAction = jsonArray.createNestedObject(); nestedMacroAction["type"] = this->actionType; nestedMacroAction["val1"] = this->val1; nestedMacroAction["val2"] = this->val2; } ESPStepperMotorServer_MacroAction *ESPStepperMotorServer_MacroAction::fromJsonObject(JsonObject macroActionJson) { int val1 = macroActionJson["val1"]; long val2 = (long)macroActionJson["val2"]; MacroActionType type = macroActionJson["type"]; return new ESPStepperMotorServer_MacroAction(type, val1, val2 ); } MacroActionType ESPStepperMotorServer_MacroAction::getType(void) { return this->actionType; } int ESPStepperMotorServer_MacroAction::getVal1(void) { return this->val1; } long ESPStepperMotorServer_MacroAction::getVal2(void) { return this->val2; } ================================================ FILE: src/ESPStepperMotorServer_MacroAction.h ================================================ #ifndef ESPStepperMotorServer_MacroAction_h #define ESPStepperMotorServer_MacroAction_h #include #include class ESPStepperMotorServer; enum MacroActionType { moveTo, moveBy, setSpeed, setAcceleration, setDeceleration, setHome, setLimitA, setLimitB, setOutputHigh, setOutputLow, triggerEmergencyStop, releaseEmergencyStop }; class ESPStepperMotorServer_MacroAction { public: ESPStepperMotorServer_MacroAction(MacroActionType actionType, int val1, long val2 = 0); bool execute(ESPStepperMotorServer *serverRef); void addSerializedInstanceToJsonArray(JsonArray jsonArray); static ESPStepperMotorServer_MacroAction * fromJsonObject(JsonObject macroActionJson); MacroActionType getType(void); int getVal1(void); long getVal2(void); private: MacroActionType actionType; int val1 = 0; long val2 = 0; }; #endif ================================================ FILE: src/ESPStepperMotorServer_MotionController.cpp ================================================ // ********************************************************* // * * // * ESP32 Stepper Motor Server - Motion Controller * // * * // * Copyright (c) Paul Kerspe, 2019 * // * * // ********************************************************** // MIT License // // Copyright (c) 2019 Paul Kerspe // // Permission is hereby granted, free of charge, to any person obtaining a copy // of this software and associated documentation files (the "Software"), to deal // in the Software without restriction, including without limitation the rights // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell // copies of the Software, and to permit persons to whom the Software is furnished // to do so, subject to the following conditions: // // The above copyright notice and this permission notice shall be included in all // copies or substantial portions of the Software. // // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE // SOFTWARE. #include // // constructor for the motion controller module // creates a freeRTOS Task that runs in the background and triggers the motion updates for the stepper driver // ESPStepperMotorServer_MotionController::ESPStepperMotorServer_MotionController(ESPStepperMotorServer *serverRef) { this->serverRef = serverRef; #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG ESPStepperMotorServer_Logger::logDebug("Motor Controller created"); #endif } void ESPStepperMotorServer_MotionController::start() { if (this->xHandle == NULL) //prevent multiple starts { disableCore0WDT(); xTaskCreate( ESPStepperMotorServer_MotionController::processMotionUpdates, /* Task function. */ "MotionControl", /* String with name of task. */ 10000, /* Stack size in bytes. */ this, /* Parameter passed as input of the task */ 2, /* Priority of the task. */ &this->xHandle); /* Task handle. */ //esp_task_wdt_delete(this->xHandle); ESPStepperMotorServer_Logger::logInfo("Motion Controller task started"); } } void ESPStepperMotorServer_MotionController::processMotionUpdates(void *parameter) { ESPStepperMotorServer_MotionController *ref = static_cast(parameter); ESPStepperMotorServer_Configuration *configuration = ref->serverRef->getCurrentServerConfiguration(); ESP_FlexyStepper **configuredFlexySteppers = configuration->getConfiguredFlexySteppers(); bool emergencySwitchFlag = false; bool allMovementsCompleted = true; #ifndef ESPStepperMotorServer_COMPILE_NO_WEB int updateCounter = 0; #endif while (true) { allMovementsCompleted = true; //update positions of all steppers / trigger stepping if needed for (byte i = 0; i < ESPServerMaxSteppers; i++) { if (configuredFlexySteppers[i]) { if (!configuredFlexySteppers[i]->processMovement()) { allMovementsCompleted = false; } } else { break; } } if (allMovementsCompleted && ref->serverRef->_isRebootScheduled) { //going for reboot since all motion is stopped and reboot has been requested Serial.println("Rebooting server now"); ESP.restart(); } //check for emergency switch if (ref->serverRef->emergencySwitchIsActive && !emergencySwitchFlag) { emergencySwitchFlag = true; ESPStepperMotorServer_Logger::logInfo("Emergency Switch triggered"); } else if (!ref->serverRef->emergencySwitchIsActive && emergencySwitchFlag) { emergencySwitchFlag = false; } #ifndef ESPStepperMotorServer_COMPILE_NO_WEB //check if we should send updated position information via websocket if (ref->serverRef->isWebserverEnabled) { updateCounter++; //we only send sproadically to reduce load and processing times if (updateCounter % 200000 == 0 && ref->serverRef->webSocketServer->count() > 0) { String positionsString = String("{"); char segmentBuffer[500]; bool isFirstSegment = true; for (byte n = 0; n < ESPServerMaxSteppers; n++) { if (configuredFlexySteppers[n]) { if (!isFirstSegment) { positionsString += ","; } sprintf(segmentBuffer, "\"s%ipos\":%ld, \"s%ivel\":%.3f", n, configuredFlexySteppers[n]->getCurrentPositionInSteps(), n, configuredFlexySteppers[n]->getCurrentVelocityInStepsPerSecond()); //maybe register as friendly class and access property directly and save some processing time positionsString += segmentBuffer; isFirstSegment = false; } } positionsString += "}"; ref->serverRef->sendSocketMessageToAllClients(positionsString.c_str(), positionsString.length()); updateCounter = 0; } } #endif } } void ESPStepperMotorServer_MotionController::stop() { vTaskDelete(this->xHandle); this->xHandle = NULL; ESPStepperMotorServer_Logger::logInfo("Motion Controller stopped"); } // -------------------------------------- End -------------------------------------- ================================================ FILE: src/ESPStepperMotorServer_MotionController.h ================================================ // ****************************************************************** // * * // * Header file for ESPStepperMotorServer_MotionController.cpp * // * * // * Copyright (c) Paul Kerspe, 2019 * // * * // ****************************************************************** // MIT License // // Copyright (c) 2019 Paul Kerspe // // Permission is hereby granted, free of charge, to any person obtaining a copy // of this software and associated documentation files (the "Software"), to deal // in the Software without restriction, including without limitation the rights // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell // copies of the Software, and to permit persons to whom the Software is furnished // to do so, subject to the following conditions: // // The above copyright notice and this permission notice shall be included in all // copies or substantial portions of the Software. // // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE // SOFTWARE. #ifndef ESPStepperMotorServer_MotionController_h #define ESPStepperMotorServer_MotionController_h #include #include #include #include class ESPStepperMotorServer; class ESPStepperMotorServer_MotionController { public: ESPStepperMotorServer_MotionController(ESPStepperMotorServer *serverRef); static void processMotionUpdates(void *parameter); void start(); void stop(); private: TaskHandle_t xHandle = NULL; ESPStepperMotorServer *serverRef; }; #endif ================================================ FILE: src/ESPStepperMotorServer_PositionSwitch.cpp ================================================ // ******************************************************************* // * * // * ESP8266 and ESP32 Stepper Motor Server - Position Switch class * // * Copyright (c) Paul Kerspe, 2019 * // * * // ******************************************************************* // // MIT License // // Copyright (c) 2019 Paul Kerspe // // Permission is hereby granted, free of charge, to any person obtaining a copy // of this software and associated documentation files (the "Software"), to deal // in the Software without restriction, including without limitation the rights // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell // copies of the Software, and to permit persons to whom the Software is furnished // to do so, subject to the following conditions: // // The above copyright notice and this permission notice shall be included in all // copies or substantial portions of the Software. // // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE // SOFTWARE. // #include int _stepperIndex; // can be -1 for emergency stop switches only byte _ioPinNumber = 255; byte _switchType; //bit mask for active state and the general type of switch String _positionName = ""; long _switchPosition = -1; ESPStepperMotorServer_Logger _logger = ESPStepperMotorServer_Logger((String)"ESPStepperMotorServer_PositionSwitch"); ESPStepperMotorServer_PositionSwitch::ESPStepperMotorServer_PositionSwitch() { } ESPStepperMotorServer_PositionSwitch::~ESPStepperMotorServer_PositionSwitch() { this->clearMacroActions(); } ESPStepperMotorServer_PositionSwitch::ESPStepperMotorServer_PositionSwitch(byte ioPin, int stepperIndex, byte switchType, String name, long switchPosition) { this->_ioPinNumber = ioPin; this->_stepperIndex = stepperIndex; this->_switchType = switchType; //this is a bit mask representing the active state (bit 1 and 2) and the general type (homing/limit/position or emergency stop switch) in one byte this->_positionName = name; this->_switchPosition = switchPosition; } void ESPStepperMotorServer_PositionSwitch::setId(byte id) { this->_switchIndex = id; } /** * the unique ID of this switch * NOTE: This ID also matches the array index of the configuration in the allConfiguredSwitches array in the Configuration class */ byte ESPStepperMotorServer_PositionSwitch::getId() { return this->_switchIndex; } int ESPStepperMotorServer_PositionSwitch::getStepperIndex(void) { return this->_stepperIndex; } byte ESPStepperMotorServer_PositionSwitch::getIoPinNumber(void) { return this->_ioPinNumber; } byte ESPStepperMotorServer_PositionSwitch::getSwitchType(void) { return this->_switchType; } String ESPStepperMotorServer_PositionSwitch::getPositionName(void) { return this->_positionName; } void ESPStepperMotorServer_PositionSwitch::setPositionName(String name) { this->_positionName = name; } long ESPStepperMotorServer_PositionSwitch::getSwitchPosition(void) { return this->_switchPosition; } void ESPStepperMotorServer_PositionSwitch::setSwitchPosition(long position) { this->_switchPosition = position; } bool ESPStepperMotorServer_PositionSwitch::isActiveHigh() { return this->isTypeBitSet(SWITCHTYPE_STATE_ACTIVE_HIGH_BIT); } bool ESPStepperMotorServer_PositionSwitch::isEmergencySwitch() { return this->isTypeBitSet(SWITCHTYPE_EMERGENCY_STOP_SWITCH_BIT); } bool ESPStepperMotorServer_PositionSwitch::isLimitSwitch() { return (this->isTypeBitSet(SWITCHTYPE_LIMITSWITCH_POS_BEGIN_BIT) || this->isTypeBitSet(SWITCHTYPE_LIMITSWITCH_POS_END_BIT) || this->isTypeBitSet(SWITCHTYPE_LIMITSWITCH_COMBINED_BEGIN_END_BIT)); } bool ESPStepperMotorServer_PositionSwitch::isTypeBitSet(byte bitToCheck) { return this->_switchType & (1 << (bitToCheck - 1)); } void ESPStepperMotorServer_PositionSwitch::addMacroAction(ESPStepperMotorServer_MacroAction *macroAction) { this->_macroActions.push_back(macroAction); } std::vector ESPStepperMotorServer_PositionSwitch::getMacroActions() { return this->_macroActions; } void ESPStepperMotorServer_PositionSwitch::clearMacroActions() { for(ESPStepperMotorServer_MacroAction *macroAction : this->_macroActions) { delete(macroAction); } this->_macroActions.clear(); } bool ESPStepperMotorServer_PositionSwitch::hasMacroActions(){ return (this->_macroActions.size() > 0); } int ESPStepperMotorServer_PositionSwitch::serializeMacroActionsToJsonArray(JsonArray macroActionsJsonArray){ for(ESPStepperMotorServer_MacroAction *macroAction : this->_macroActions) { macroAction->addSerializedInstanceToJsonArray(macroActionsJsonArray); } return this->_macroActions.size(); } ================================================ FILE: src/ESPStepperMotorServer_PositionSwitch.h ================================================ #ifndef ESPStepperMotorServer_PositionSwitch_h #define ESPStepperMotorServer_PositionSwitch_h #include #include #include #include #include #define SWITCHTYPE_STATE_ACTIVE_HIGH_BIT 1 #define SWITCHTYPE_STATE_ACTIVE_LOW_BIT 2 #define SWITCHTYPE_LIMITSWITCH_POS_BEGIN_BIT 3 #define SWITCHTYPE_LIMITSWITCH_POS_END_BIT 4 #define SWITCHTYPE_POSITION_SWITCH_BIT 5 #define SWITCHTYPE_EMERGENCY_STOP_SWITCH_BIT 6 #define SWITCHTYPE_LIMITSWITCH_COMBINED_BEGIN_END_BIT 7 //size calculated using https://arduinojson.org/v6/assistant/ #define RESERVED_JSON_SIZE_ESPStepperMotorServer_PositionSwitch 170 class ESPStepperMotorServer_MacroAction; class ESPStepperMotorServer_PositionSwitch { friend class ESPStepperMotorServer; public: ESPStepperMotorServer_PositionSwitch(); ~ESPStepperMotorServer_PositionSwitch(); ESPStepperMotorServer_PositionSwitch(byte ioPin, int stepperIndex, byte switchType, String name = "", long switchPosition = 0); /** * setter to set the id of this switch. * Only use this if you know what you are doing */ void setId(byte id); /** * get the id of the switch */ byte getId(); int getStepperIndex(void); byte getIoPinNumber(void); /** * return the type of this switch if set. * It indicates whether the switch as limit, position or emergency switch * See constants * SWITCHTYPE_LIMITSWITCH_POS_BEGIN_BIT * SWITCHTYPE_LIMITSWITCH_POS_END_BIT * SWITCHTYPE_LIMITSWITCH_COMBINED_BEGIN_END_BIT * SWITCHTYPE_POSITION_SWITCH_BIT * SWITCHTYPE_EMERGENCY_STOP_SWITCH_BIT */ byte getSwitchType(void); String getPositionName(void); void setPositionName(String name); bool isActiveHigh(); bool isEmergencySwitch(); bool isLimitSwitch(); bool isTypeBitSet(byte bitToCheck); long getSwitchPosition(void); void setSwitchPosition(long position); void addMacroAction(ESPStepperMotorServer_MacroAction *macroAction); std::vector getMacroActions(); bool hasMacroActions(void); void clearMacroActions(void); int serializeMacroActionsToJsonArray(JsonArray macroActionsJsonArray); private: byte _stepperIndex; byte _switchIndex; byte _ioPinNumber = 255; byte _switchType = 0; //this is a bit mask representing the active state (bit 1 and 2) and the general type (homing/limit/position or emergency stop switch) in one byte String _positionName; long _switchPosition; ESPStepperMotorServer_Logger _logger; std::vector _macroActions; }; #endif ================================================ FILE: src/ESPStepperMotorServer_RestAPI.cpp ================================================ // ********************************************************* // * * // * ESP8266 and ESP32 Stepper Motor Server Rest API * // * * // * Copyright (c) Paul Kerspe, 2019 * // * * // ********************************************************** // MIT License // // Copyright (c) 2019 Paul Kerspe // // Permission is hereby granted, free of charge, to any person obtaining a copy // of this software and associated documentation files (the "Software"), to deal // in the Software without restriction, including without limitation the rights // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell // copies of the Software, and to permit persons to whom the Software is furnished // to do so, subject to the following conditions: // // The above copyright notice and this permission notice shall be included in all // copies or substantial portions of the Software. // // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE // SOFTWARE. #include "ESPStepperMotorServer_RestAPI.h" ESPStepperMotorServer_Logger *logger; ESPStepperMotorServer *_stepperMotorServer; // --------------------------------------------------------------------------------- // Setup functions // --------------------------------------------------------------------------------- // // constructor for the rest endpoint provider // ESPStepperMotorServer_RestAPI::ESPStepperMotorServer_RestAPI(ESPStepperMotorServer *stepperMotorServer) { this->_stepperMotorServer = stepperMotorServer; #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG ESPStepperMotorServer_Logger::logDebug("ESPStepperMotorServer_RestAPI instance created"); #endif } /** * this function is used to register all handlers for the rest API endpoints of the ESPStepperMotorServer */ void ESPStepperMotorServer_RestAPI::registerRestEndpoints(AsyncWebServer *httpServer) { // GET /api/status // get the current stepper server status report including the following information: version string of the server, wifi information (wifi mode, IP address), spiffs information (total space and free space) httpServer->on("/api/status", HTTP_GET, [this](AsyncWebServerRequest *request) { this->logDebugRequestUrl(request); String output = String(""); this->_stepperMotorServer->getServerStatusAsJsonString(output); //populate string with json AsyncWebServerResponse *response = request->beginResponse(200, "application/json", output); request->send(response); }); // GET /api/steppers/position?id= httpServer->on("/api/steppers/position", HTTP_GET, [this](AsyncWebServerRequest *request) { this->logDebugRequestUrl(request); if (request->hasParam("id")) { const byte stepperIndex = request->getParam("id")->value().toInt(); ESPStepperMotorServer_StepperConfiguration *stepper = this->_stepperMotorServer->getCurrentServerConfiguration()->getStepperConfiguration(stepperIndex); if (stepperIndex < 0 || stepperIndex >= ESPServerMaxSteppers || stepper == NULL) { request->send(404, "application/json", "{\"error\": \"Invalid stepper id\"}"); return; } String output; const int docSize = 60; StaticJsonDocument doc; JsonObject root = doc.to(); root["mm"] = stepper->getFlexyStepper()->getCurrentPositionInMillimeters(); root["revs"] = stepper->getFlexyStepper()->getCurrentPositionInRevolutions(); root["steps"] = stepper->getFlexyStepper()->getCurrentPositionInSteps(); serializeJson(root, output); AsyncWebServerResponse *response = request->beginResponse(200, "application/json", output); request->send(response); #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG if (ESPStepperMotorServer_Logger::isDebugEnabled()) { ESPStepperMotorServer_Logger::logDebugf("ArduinoJSON document size uses %i bytes from alocated %i bytes", doc.memoryUsage(), docSize); } #endif } else { request->send(400, "application/json", "{\"error\": \"Missing id paramter\"}"); return; } }); // POST /api/steppers/returnhome // endpoint trigger movement for stepper until home is reached (indicated by kill switch) // see documentation of handler function for details httpServer->on("/api/steppers/returnhome", HTTP_POST, [this](AsyncWebServerRequest *request) { this->logDebugRequestUrl(request); this->handleHomingRequest(request); }); // POST /api/steppers/moveby // endpoint to set a new RELATIVE target position for the stepper motor in either mm, revs or steps // post parameters: id, unit, value // optional parameters: speed, accel, decel httpServer->on("/api/steppers/moveby", HTTP_POST, [this](AsyncWebServerRequest *request) { this->logDebugRequestUrl(request); if (request->hasParam("id")) { int stepperIndex = request->getParam("id")->value().toInt(); ESPStepperMotorServer_StepperConfiguration *stepper = this->_stepperMotorServer->getCurrentServerConfiguration()->getStepperConfiguration(stepperIndex); if (stepper == NULL) { request->send(404, "application/json", "{\"error\": \"No stepper configuration found for given id\"}"); return; } if (request->hasParam("speed")) { float speed = request->getParam("speed")->value().toFloat(); if (speed > 0) { stepper->getFlexyStepper()->setSpeedInStepsPerSecond(speed); } } if (request->hasParam("accel")) { float accel = request->getParam("accel")->value().toFloat(); if (accel > 0) { stepper->getFlexyStepper()->setAccelerationInStepsPerSecondPerSecond(accel); //in case deceleration is not explicitly given, we just use the same value stepper->getFlexyStepper()->setDecelerationInStepsPerSecondPerSecond(accel); } } if (request->hasParam("decel")) { float decel = request->getParam("decel")->value().toFloat(); if (decel > 0) { stepper->getFlexyStepper()->setDecelerationInStepsPerSecondPerSecond(decel); } } if (request->hasParam("value") && request->hasParam("unit")) { String unit = request->getParam("unit")->value(); float distance = request->getParam("value")->value().toFloat(); if (unit == "mm") { stepper->getFlexyStepper()->setTargetPositionRelativeInMillimeters(distance); } else if (unit == "revs") { stepper->getFlexyStepper()->setTargetPositionRelativeInRevolutions(distance); } else if (unit == "steps") { stepper->getFlexyStepper()->setTargetPositionRelativeInSteps(distance); } else { request->send(400, "application/json", "{\"error\": \"Unit must be one of: revs, steps, mm\"}"); return; } request->send(204); return; } } request->send(400, "application/json", "{\"error\": \"Missing id paramter\"}"); }); // POST /api/steppers/position // endpoint to set a new absolute target position for the stepper motor in either mm, revs or steps // post parameters: id, unit, value // optional parameters: speed, accel, decel httpServer->on("/api/steppers/position", HTTP_POST, [this](AsyncWebServerRequest *request) { this->logDebugRequestUrl(request); if (request->hasParam("id", true)) { int stepperIndex = request->getParam("id", true)->value().toInt(); ESPStepperMotorServer_StepperConfiguration *stepper = this->_stepperMotorServer->getCurrentServerConfiguration()->getStepperConfiguration(stepperIndex); if (stepper == NULL) { request->send(404, "application/json", "{\"error\": \"No stepper configuration found for given id\"}"); return; } if (request->hasParam("speed")) { float speed = request->getParam("speed")->value().toFloat(); if (speed > 0) { stepper->getFlexyStepper()->setSpeedInStepsPerSecond(speed); } } if (request->hasParam("accel")) { float accel = request->getParam("accel")->value().toFloat(); if (accel > 0) { stepper->getFlexyStepper()->setAccelerationInStepsPerSecondPerSecond(accel); //in case deceleration is not explicitly given, we just use the same value stepper->getFlexyStepper()->setDecelerationInStepsPerSecondPerSecond(accel); } } if (request->hasParam("decel")) { float decel = request->getParam("decel")->value().toFloat(); if (decel > 0) { stepper->getFlexyStepper()->setDecelerationInStepsPerSecondPerSecond(decel); } } if (request->hasParam("value", true) && request->hasParam("unit", true)) { String unit = request->getParam("unit", true)->value(); float position = request->getParam("value", true)->value().toFloat(); if (unit == "mm") { stepper->getFlexyStepper()->setTargetPositionInMillimeters(position); } else if (unit == "revs") { stepper->getFlexyStepper()->setTargetPositionInRevolutions(position); } else if (unit == "steps") { stepper->getFlexyStepper()->setTargetPositionInSteps(position); } else { request->send(400); return; } request->send(204); return; } } request->send(400); }); // GET /api/steppers/stop?id= // endpoint to send a stop signal to the selected stepper httpServer->on("/api/steppers/stop", HTTP_GET, [this](AsyncWebServerRequest *request) { this->logDebugRequestUrl(request); if (request->hasParam("id", false)) { int stepperIndex = request->getParam("id", false)->value().toInt(); ESPStepperMotorServer_StepperConfiguration *stepper = this->_stepperMotorServer->getCurrentServerConfiguration()->getStepperConfiguration(stepperIndex); if (stepper == NULL) { request->send(404); return; } else { stepper->getFlexyStepper()->setTargetPositionToStop(); request->send(204); return; } } else { request->send(400, "application/json", "{\"error\": \"Missing id paramter\"}"); return; } }); // GET /api/emergencystop/trigger // endpoint to send a emergencystop signal for all steppers httpServer->on("/api/emergencystop/trigger", HTTP_GET, [this](AsyncWebServerRequest *request) { this->logDebugRequestUrl(request); this->_stepperMotorServer->performEmergencyStop(); request->send(204); return; }); // GET /api/emergencystop/revoke // endpoint to revoke the emergencystop signal for all steppers httpServer->on("/api/emergencystop/revoke", HTTP_GET, [this](AsyncWebServerRequest *request) { this->logDebugRequestUrl(request); this->_stepperMotorServer->revokeEmergencyStop(); request->send(204); return; }); // GET /api/steppers // GET /api/steppers?id= // endpoint to list all configured steppers or a specific one if "id" query parameter is given httpServer->on("/api/steppers", HTTP_GET, [this](AsyncWebServerRequest *request) { this->logDebugRequestUrl(request); String output; if (request->hasParam("id")) { int stepperIndex = request->getParam("id")->value().toInt(); if (stepperIndex < 0 || stepperIndex >= ESPServerMaxSteppers) { request->send(404); return; } StaticJsonDocument<400> doc; JsonObject root = doc.to(); JsonObject stepperDetails = root.createNestedObject("stepper"); this->populateStepperDetailsToJsonObject(stepperDetails, this->_stepperMotorServer->getCurrentServerConfiguration()->getStepperConfiguration(stepperIndex), stepperIndex); serializeJson(root, output); } else { const int docSize = 420 * ESPServerMaxSteppers; StaticJsonDocument doc; JsonObject root = doc.to(); JsonArray steppers = root.createNestedArray("steppers"); for (int i = 0; i < ESPServerMaxSteppers; i++) { JsonObject stepperDetails = steppers.createNestedObject(); this->populateStepperDetailsToJsonObject(stepperDetails, this->_stepperMotorServer->getCurrentServerConfiguration()->getStepperConfiguration(i), i); } serializeJson(root, output); ESPStepperMotorServer_Logger::logDebugf("ArduinoJSON document size uses %i bytes from alocated %i bytes\n", doc.memoryUsage(), docSize); } AsyncWebServerResponse *response = request->beginResponse(200, "application/json", output); request->send(response); }); // DELETE /api/steppers?id= // delete an existing stepper configuration entry httpServer->on("/api/steppers", HTTP_DELETE, [this](AsyncWebServerRequest *request) { this->logDebugRequestUrl(request); this->handleDeleteStepperRequest(request, true); }); // POST /api/steppers // add a new stepper configuration entry httpServer->on( "/api/steppers", HTTP_POST, [](AsyncWebServerRequest *request) {}, NULL, [this](AsyncWebServerRequest *request, uint8_t *data, size_t len, size_t index, size_t total) { this->logDebugRequestUrl(request); this->handlePostStepperRequest(request, data, len, index, total, -1); }); // PUT /api/steppers?id= // upate an existing stepper configuration entry httpServer->on( "/api/steppers", HTTP_PUT, [](AsyncWebServerRequest *request) {}, NULL, [this](AsyncWebServerRequest *request, uint8_t *data, size_t len, size_t index, size_t total) { this->logDebugRequestUrl(request); int stepperIndex = request->getParam("id")->value().toInt(); this->handlePostStepperRequest(request, data, len, index, total, stepperIndex); }); // GET /api/switches/status // GET /api/switches/status?id= // get the current switch status (active, inactive) of either one specific switch or all switches (returned as a bit mask in MSB order) httpServer->on("/api/switches/status", HTTP_GET, [this](AsyncWebServerRequest *request) { this->logDebugRequestUrl(request); if (request->hasParam("id")) { int switchIndex = request->getParam("id")->value().toInt(); if (this->_stepperMotorServer->getCurrentServerConfiguration()->getSwitch(switchIndex) == NULL) { request->send(404); return; } request->send(200, "application/json", (String) "{ \"status\": \"" + this->_stepperMotorServer->getPositionSwitchStatus(switchIndex) + (String) "\"}"); } else { String output = "{ \"status\": \""; for (int i = ESPServerSwitchStatusRegisterCount - 1; i >= 0; i--) { this->_stepperMotorServer->getFormattedPositionSwitchStatusRegister(i, output); } request->send(200, "application/json", output + "\"}"); } }); // GET /api/switches // GET /api/switches?id= // endpoint to list all position switch configurations or a specific configuration if the "id" query parameter is given httpServer->on("/api/switches", HTTP_GET, [this](AsyncWebServerRequest *request) { this->logDebugRequestUrl(request); String output; const int switchObjectSize = JSON_OBJECT_SIZE(8) + 80; //80 is for Strings names if (request->hasParam("id")) { int switchIndex = request->getParam("id")->value().toInt(); if (this->_stepperMotorServer->getCurrentServerConfiguration()->getSwitch(switchIndex) == NULL) { request->send(404, "application/json", "{\"error\": \"No switch found for the given id\"}"); return; } StaticJsonDocument doc; JsonObject root = doc.to(); this->populateSwitchDetailsToJsonObject(root, this->_stepperMotorServer->getCurrentServerConfiguration()->getSwitch(switchIndex), switchIndex); serializeJson(root, output); #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG if (ESPStepperMotorServer_Logger::isDebugEnabled()) { ESPStepperMotorServer_Logger::logDebugf("ArduinoJSON document size uses %i bytes from alocated %i bytes\n", doc.memoryUsage(), switchObjectSize); } #endif } else { const int docSize = switchObjectSize * ESPServerMaxSwitches; StaticJsonDocument doc; JsonObject root = doc.to(); JsonArray switches = root.createNestedArray("switches"); //TODO instead of doing a loop, implement function getAllConfiguredSwitches() for (int i = 0; i < ESPServerMaxSwitches; i++) { if (this->_stepperMotorServer->getCurrentServerConfiguration()->getSwitch(i)) { JsonObject switchDetails = switches.createNestedObject(); this->populateSwitchDetailsToJsonObject(switchDetails, this->_stepperMotorServer->getCurrentServerConfiguration()->getSwitch(i), i); } } serializeJson(root, output); #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG if (ESPStepperMotorServer_Logger::isDebugEnabled()) { ESPStepperMotorServer_Logger::logDebugf("ArduinoJSON document size uses %i bytes from alocated %i bytes\n", doc.memoryUsage(), docSize); } #endif } AsyncWebServerResponse *response = request->beginResponse(200, "application/json", output); request->send(response); }); // POST /api/switches // endpoint to add a new switch configuration httpServer->on( "/api/switches", HTTP_POST, [](AsyncWebServerRequest *request) {}, NULL, [this](AsyncWebServerRequest *request, uint8_t *data, size_t len, size_t index, size_t total) { this->logDebugRequestUrl(request); this->handlePostSwitchRequest(request, data, len, index, total); }); // PUT /api/switches?id= // endpoint to update an existing switch configuration httpServer->on( "/api/switches", HTTP_PUT, [](AsyncWebServerRequest *request) {}, NULL, [this](AsyncWebServerRequest *request, uint8_t *data, size_t len, size_t index, size_t total) { this->logDebugRequestUrl(request); int switchIndex = request->getParam("id")->value().toInt(); this->handlePostSwitchRequest(request, data, len, index, total, switchIndex); }); // DELETE /api/switches?id= // delete a specific switch configuration httpServer->on("/api/switches", HTTP_DELETE, [this](AsyncWebServerRequest *request) { this->logDebugRequestUrl(request); this->handleDeleteSwitchRequest(request, true); }); // GET /api/encoders // GET /api/encoders?id= // endpoint to list all rotary encoder configurations or a specific configuration if the "id" query parameter is given httpServer->on("/api/encoders", HTTP_GET, [this](AsyncWebServerRequest *request) { this->logDebugRequestUrl(request); String output; const int rotaryEncoderObjectSize = JSON_OBJECT_SIZE(8) + 80; //80 is for Strings names if (request->hasParam("id")) { int rotaryEncoderIndex = request->getParam("id")->value().toInt(); if (this->_stepperMotorServer->getCurrentServerConfiguration()->getRotaryEncoder(rotaryEncoderIndex) == NULL) { request->send(404); return; } StaticJsonDocument doc; JsonObject root = doc.to(); this->populateRotaryEncoderDetailsToJsonObject(root, this->_stepperMotorServer->getCurrentServerConfiguration()->getRotaryEncoder(rotaryEncoderIndex), rotaryEncoderIndex); serializeJson(root, output); #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG if (ESPStepperMotorServer_Logger::isDebugEnabled()) { ESPStepperMotorServer_Logger::logDebugf("ArduinoJSON document size uses %i bytes from alocated %i bytes\n", doc.memoryUsage(), rotaryEncoderObjectSize); } #endif } else { const int docSize = rotaryEncoderObjectSize * ESPServerMaxRotaryEncoders; StaticJsonDocument doc; JsonObject root = doc.to(); JsonArray encoders = root.createNestedArray("rotaryEncoders"); for (int i = 0; i < ESPServerMaxRotaryEncoders; i++) { if (this->_stepperMotorServer->getCurrentServerConfiguration()->getRotaryEncoder(i) != NULL) { JsonObject encoderDetails = encoders.createNestedObject(); this->populateRotaryEncoderDetailsToJsonObject(encoderDetails, this->_stepperMotorServer->getCurrentServerConfiguration()->getRotaryEncoder(i), i); } } serializeJson(root, output); #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG if (ESPStepperMotorServer_Logger::isDebugEnabled()) { ESPStepperMotorServer_Logger::logDebugf("ArduinoJSON document size uses %i bytes from alocated %i bytes\n", doc.memoryUsage(), docSize); } #endif } AsyncWebServerResponse *response = request->beginResponse(200, "application/json", output); request->send(response); }); // POST /api/encoders // endpoint to add a new rotary encoder configuration httpServer->on( "/api/encoders", HTTP_POST, [](AsyncWebServerRequest *request) {}, NULL, [this](AsyncWebServerRequest *request, uint8_t *data, size_t len, size_t index, size_t total) { this->logDebugRequestUrl(request); this->handlePostRotaryEncoderRequest(request, data, len, index, total); }); // PUT /api/encoders?id= // endpoint to update an existing rotary encoder configuration (will effectively delete the old configuraiton and write a new one at the same position) httpServer->on( "/api/encoders", HTTP_PUT, [](AsyncWebServerRequest *request) {}, NULL, [this](AsyncWebServerRequest *request, uint8_t *data, size_t len, size_t index, size_t total) { this->logDebugRequestUrl(request); int deleteRC = this->handleDeleteRotaryEncoderRequest(request, false); if (deleteRC == 204) { int encoderIndex = request->getParam("id")->value().toInt(); this->handlePostRotaryEncoderRequest(request, data, len, index, total, encoderIndex); } else { request->send(deleteRC, "application/json", "{\"error\": \"Failed to update rotary encoder\"}"); } }); // DELETE /api/encoders?id= // delete a specific rotary encoder configuration httpServer->on("/api/encoders", HTTP_DELETE, [this](AsyncWebServerRequest *request) { this->logDebugRequestUrl(request); this->handleDeleteRotaryEncoderRequest(request, true); }); // GET /api/config/save // endpoint to save the current IN MEMORY configuration with all settings to SPIFFS and therefore persist it to survive a reboot httpServer->on("/api/config/save", HTTP_GET, [this](AsyncWebServerRequest *request) { this->logDebugRequestUrl(request); ESPStepperMotorServer_Configuration *config = this->_stepperMotorServer->getCurrentServerConfiguration(); bool saved = config->saveCurrentConfiguationToSpiffs(); if (saved) { request->send(204); } else { request->send(500, "application/json", "{\"error\": \"failed to save configuraiton to SPIFFS\"}"); } }); // GET /api/config // endpoint to list the current IN MEMORY configuration with all settings (passwords will be hidden though) httpServer->on("/api/config", HTTP_GET, [this](AsyncWebServerRequest *request) { this->logDebugRequestUrl(request); ESPStepperMotorServer_Configuration *config = this->_stepperMotorServer->getCurrentServerConfiguration(); request->send(200, "application/json", config->getCurrentConfigurationAsJSONString(true, false)); }); // GET /api/outputs // GET /api/outputs?id= // GET /api/outputs/status?id= // PUT /api/outputs/status?id= // POST /api/outputs // PUT /api/outputs?id= // DELETE /api/outputs?id= } /** * handler for the REST endpoint to perform a homing run. * This will call the goToLimitAndSetAsHome() function in the flexyStepper instance. * It will require that a home/limit switch is configured for this stepper, otherwise stepper will "never" (an absolute limit of 2000000000 steps is configured by default to somewhat limit the movement) come to a halt * Required POST parameters: * id (id of the stepper motor to pefrom the homing command for) * speed: the speed in steps per second to perform the homing command with * Optional POST parameters: * switchId: the id of the configured switch to use as limit switch, if parameter is omited the position switch from the configurtration of the stepper motor will be used, if none is configured, operation will fail) * accel: the acceleration for the homing procdeure in steps/sec^2, if ommitted the previously defined acceleration in the flexy stepper instance will be used * maxSteps: this parameter defines the maximum number of steps to perform before cancelling the homing procedure. This is kind of a safeguard to prevent endless spinning of the stepper motor. Defaults to 2000000000 steps */ void ESPStepperMotorServer_RestAPI::handleHomingRequest(AsyncWebServerRequest *request) { this->logDebugRequestUrl(request); if (!request->hasParam("id")) { request->send(400, "application/json", "{\"error\": \"Missing stepper id parameter\"}"); return; } int stepperIndex = request->getParam("id")->value().toInt(); ESPStepperMotorServer_StepperConfiguration *stepperConfiguration = this->_stepperMotorServer->getCurrentServerConfiguration()->getStepperConfiguration(stepperIndex); if (stepperConfiguration == NULL) { request->send(404, "application/json", "{\"error\": \"No stepper configuration found for given stepper id\"}"); return; } float speedInStepsPerSecond = 0; if (request->hasParam("speed")) { speedInStepsPerSecond = request->getParam("speed")->value().toFloat(); if (speedInStepsPerSecond <= 0) { request->send(400, "application/json", "{\"error\": \"Value for homing speed (in steps/second) must be larger than 0\"}"); return; } } else { request->send(400, "application/json", "{\"error\": \"Missing parameter for speed (in steps/second)\"}"); return; } float accelInStepPerSecondSquare = 0; if (request->hasParam("accel")) { accelInStepPerSecondSquare = request->getParam("accel")->value().toFloat(); if (accelInStepPerSecondSquare <= 0) { request->send(400, "application/json", "{\"error\": \"Acceleration value must be larger than 0\"}"); return; } } unsigned int maxSteps = 2000000000; if (request->hasParam("maxSteps")) { maxSteps = request->getParam("maxSteps")->value().toInt(); if (maxSteps < 1) { request->send(400, "application/json", "{\"error\": \"Max number of steps during homing must be larger than 0\"}"); return; } } ESPStepperMotorServer_PositionSwitch *switchConfig; signed char directionTowardHome = 1; signed char forcedDirectionTowardHome = 0; if (request->hasParam("direction")) { forcedDirectionTowardHome = request->getParam("direction")->value().toInt(); if (forcedDirectionTowardHome != 1 && forcedDirectionTowardHome != -1) { request->send(400, "application/json", "{\"error\": \"Invalid direction value given. Allowed values are 1 and -1\"}"); return; } } byte gpioPinForSwitch = 0; //TOOD: implement proper ISR handling for custom switch parameter if not linked to existing stepper if (request->hasParam("switchId")) { int switchIndex = request->getParam("switchId")->value().toInt(); switchConfig = this->_stepperMotorServer->getCurrentServerConfiguration()->getSwitch(switchIndex); if (switchConfig == NULL) { request->send(400, "application/json", "{\"error\": \"No switch configuration found for given switch id\"}"); return; } gpioPinForSwitch = switchConfig->getIoPinNumber(); //TODO: this detection is not exactely precise, since the switch could also be a combined Begin / End switch if (switchConfig->isTypeBitSet(SWITCHTYPE_LIMITSWITCH_POS_BEGIN_BIT)) { directionTowardHome = -1; } } else { //Try to find pin by looking for configured limit switches of type homing switch for selected stepper motor config switchConfig = this->_stepperMotorServer->getCurrentServerConfiguration()->getFirstConfiguredLimitSwitchForStepper(stepperIndex); if (switchConfig == NULL) { request->send(400, "application/json", "{\"error\": \"No existing limit switch configuration found the stepper with the given id\"}"); return; } gpioPinForSwitch = switchConfig->getIoPinNumber(); // determine direction section for the case no explicit switch ID was provided if (switchConfig->isTypeBitSet(SWITCHTYPE_LIMITSWITCH_POS_BEGIN_BIT)) { directionTowardHome = -1; } } ESPStepperMotorServer_Logger::logDebugf("Received homing request for stepper with id %i and limit switch on GPIO %i. Homing speed to be set to %.2f steps per second. Max step limit set to %i\n", stepperIndex, gpioPinForSwitch, speedInStepsPerSecond, maxSteps); ESP_FlexyStepper *stepper = stepperConfiguration->getFlexyStepper(); if (speedInStepsPerSecond > 0) { stepper->setSpeedInStepsPerSecond(speedInStepsPerSecond); } if (accelInStepPerSecondSquare > 0) { stepper->setAccelerationInStepsPerSecondPerSecond(accelInStepPerSecondSquare); } if (forcedDirectionTowardHome != 0) { stepper->setDirectionToHome(forcedDirectionTowardHome); } else { stepper->setDirectionToHome(directionTowardHome); } stepper->goToLimitAndSetAsHome(NULL, maxSteps); request->send(200, "application/json", "{\"status\": \"homing procedure started\"}"); return; } void ESPStepperMotorServer_RestAPI::populateSwitchDetailsToJsonObject(JsonObject &switchDetails, ESPStepperMotorServer_PositionSwitch *positionSwitch, int index) { switchDetails["id"] = index; switchDetails["ioPin"] = positionSwitch->getIoPinNumber(); switchDetails["name"] = positionSwitch->getPositionName(); switchDetails["stepperId"] = positionSwitch->getStepperIndex(); switchDetails["type"] = positionSwitch->getSwitchType(); switchDetails["isActiveHighType"] = positionSwitch->isActiveHigh(); switchDetails["switchPosition"] = positionSwitch->getSwitchPosition(); if (positionSwitch->hasMacroActions()) { JsonArray macroActions = switchDetails.createNestedArray(this->_stepperMotorServer->getCurrentServerConfiguration()->JSON_SECTION_NAME_SWITCH_CONFIGURATION_MACROACTIONS); positionSwitch->serializeMacroActionsToJsonArray(macroActions); } } void ESPStepperMotorServer_RestAPI::populateRotaryEncoderDetailsToJsonObject(JsonObject &rotaryEncoderDetails, ESPStepperMotorServer_RotaryEncoder *rotaryEncoder, int index) { rotaryEncoderDetails["id"] = index; rotaryEncoderDetails["ioPinA"] = rotaryEncoder->getPinAIOPin(); rotaryEncoderDetails["ioPinB"] = rotaryEncoder->getPinBIOPin(); rotaryEncoderDetails["name"] = rotaryEncoder->getDisplayName(); rotaryEncoderDetails["stepMultiplier"] = rotaryEncoder->getStepMultiplier(); rotaryEncoderDetails["stepperId"] = rotaryEncoder->getStepperIndex(); } void ESPStepperMotorServer_RestAPI::populateStepperDetailsToJsonObject(JsonObject &stepperDetails, ESPStepperMotorServer_StepperConfiguration *stepper, int index) { stepperDetails["id"] = index; stepperDetails["configured"] = (stepper == NULL) ? "false" : "true"; if (stepper != NULL) { stepperDetails["name"] = stepper->getDisplayName(); stepperDetails["stepPin"] = stepper->getStepIoPin(); stepperDetails["dirPin"] = stepper->getDirectionIoPin(); stepperDetails["brakePin"] = stepper->getBrakeIoPin(); stepperDetails["brakePinActiveState"] = stepper->getBrakePinActiveState(); stepperDetails["brakeEngageDelayMs"] = stepper->getBrakeEngageDelayMs(); stepperDetails["brakeReleaseDelayMs"] = stepper->getBrakeReleaseDelayMs(); stepperDetails["stepsPerMM"] = stepper->getStepsPerMM(); stepperDetails["stepsPerRev"] = stepper->getStepsPerRev(); stepperDetails["microsteppingDivisor"] = stepper->getMicrostepsPerStep(); JsonObject position = stepperDetails.createNestedObject("position"); position["mm"] = stepper->getFlexyStepper()->getCurrentPositionInMillimeters(); position["revs"] = stepper->getFlexyStepper()->getCurrentPositionInRevolutions(); position["steps"] = stepper->getFlexyStepper()->getCurrentPositionInSteps(); JsonObject stepperStatus = stepperDetails.createNestedObject("velocity"); stepperStatus["rev_s"] = stepper->getFlexyStepper()->getCurrentVelocityInRevolutionsPerSecond(); stepperStatus["mm_s"] = stepper->getFlexyStepper()->getCurrentVelocityInMillimetersPerSecond(); stepperStatus["steps_s"] = stepper->getFlexyStepper()->getCurrentVelocityInStepsPerSecond(); stepperDetails["stopped"] = stepper->getFlexyStepper()->motionComplete(); } } void ESPStepperMotorServer_RestAPI::logDebugRequestUrl(AsyncWebServerRequest *request) { #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG if (ESPStepperMotorServer_Logger::isDebugEnabled()) { int params = request->params(); ESPStepperMotorServer_Logger::logDebug((String)request->methodToString() + " called" + request->url() + ((params > 0) ? " with parameters: " : ""), (params == 0)); for (int i = 0; i < params; i++) { const AsyncWebParameter *p = request->getParam(i); if (!p->isFile() && !p->isPost()) { ESPStepperMotorServer_Logger::logDebug(p->name() + "=" + p->value() + ((i < params - 1) ? ", " : ""), (i == params - 1), true); } } } #endif } // request handlers void ESPStepperMotorServer_RestAPI::handlePostStepperRequest(AsyncWebServerRequest *request, uint8_t *data, size_t len, size_t index, size_t total, int stepperIndex) { StaticJsonDocument<500> doc; DeserializationError error = deserializeJson(doc, (const char *)data); if (error) { request->send(400, "application/json", "{\"error\": \"Invalid JSON request, deserialization failed\"}"); ESPStepperMotorServer_Logger::logWarningf("Error while trying to deserialize JSON request: %s", error.c_str()); } else { if (doc.containsKey("name") && doc.containsKey("stepPin") && doc.containsKey("dirPin") && doc.containsKey("stepsPerMM") && doc.containsKey("stepsPerRev") && doc.containsKey("microsteppingDivisor")) { const char *name = doc["name"]; int stepPin = doc["stepPin"]; int dirPin = doc["dirPin"]; int stepsPerMM = doc["stepsPerMM"]; int stepsPerRev = doc["stepsPerRev"]; int microsteppingDivisor = doc["microsteppingDivisor"]; int brakePin = doc["brakePin"]; int brakePinActiveState = doc["brakePinActiveState"]; int brakeEngageDelayMs = doc["brakeEngageDelayMs"]; int brakeReleaseDelayMs = doc["brakeReleaseDelayMs"]; if (stepPin >= 0 && stepPin <= ESPStepperHighestAllowedIoPin && dirPin >= 0 && dirPin <= ESPStepperHighestAllowedIoPin && dirPin != stepPin) { ESPStepperMotorServer_StepperConfiguration *stepper = this->_stepperMotorServer->getCurrentServerConfiguration()->getStepperConfiguration(stepperIndex); //check if pins are already in use by a stepper or switch configuration (that is not the current stepper to be updated) if (this->_stepperMotorServer->isIoPinUsed(stepPin) && (stepper == NULL || stepper->getStepIoPin() != stepPin)) { request->send(400, "application/json", "{\"error\": \"The given STEP IO pin is already used by another stepper or a switch configuration\"}"); } else if (this->_stepperMotorServer->isIoPinUsed(dirPin) && (stepper == NULL || stepper->getDirectionIoPin() != dirPin)) { request->send(400, "application/json", "{\"error\": \"The given DIRECTION IO pin is already used by another stepper or a switch configuration\"}"); } else if (brakePin >= 0 && brakePin != ESPStepperMotorServer_StepperConfiguration::ESPServerStepperUnsetIoPinNumber && this->_stepperMotorServer->isIoPinUsed(brakePin) && (stepper == NULL || stepper->getBrakeIoPin() != brakePin)) { request->send(400, "application/json", "{\"error\": \"The given BRAKE IO pin is already used by another stepper or a switch configuration\"}"); } else { int newId = -1; ESPStepperMotorServer_StepperConfiguration *stepperToAdd = new ESPStepperMotorServer_StepperConfiguration(stepPin, dirPin); stepperToAdd->setDisplayName(name); stepperToAdd->setStepsPerMM(stepsPerMM); stepperToAdd->setStepsPerRev(stepsPerRev); stepperToAdd->setMicrostepsPerStep(microsteppingDivisor); if (brakePin != ESPStepperMotorServer_StepperConfiguration::ESPServerStepperUnsetIoPinNumber) { stepperToAdd->setBrakeIoPin(brakePin, brakePinActiveState); } stepperToAdd->setBrakeEngageDelayMs(brakeEngageDelayMs); stepperToAdd->setBrakeReleaseDelayMs(brakeReleaseDelayMs); if (stepperIndex == -1) { newId = this->_stepperMotorServer->addOrUpdateStepper(stepperToAdd); } else { //"update" existing stepper config which basically means we store it at a specific index newId = stepperIndex; this->_stepperMotorServer->addOrUpdateStepper(stepperToAdd, stepperIndex); } AsyncResponseStream *response = request->beginResponseStream("application/json"); response->setCode(200); response->printf("{\"id\": %i}", newId); request->send(response); } } else { request->send(400, "application/json", "{\"error\": \"Invalid IO pin number given or step and dir pin are the same\"}"); } } else { request->send(400, "application/json", "{\"error\": \"Invalid request, missing one ore more required parameters: name, stepPin, dirPin, stepsPerMM, stepsPerRev, microsteppingDivisor\"}"); } } } int ESPStepperMotorServer_RestAPI::handleDeleteStepperRequest(AsyncWebServerRequest *request, boolean sendResponse) { if (request->hasParam("id")) { int stepperIndex = request->getParam("id")->value().toInt(); if (stepperIndex < 0 || stepperIndex >= ESPServerMaxSteppers || this->_stepperMotorServer->getCurrentServerConfiguration()->getStepperConfiguration(stepperIndex) != NULL) { this->_stepperMotorServer->removeStepper(stepperIndex); if (sendResponse) { request->send(204); } return 204; } } if (sendResponse) { request->send(404, "application/json", "{\"error\": \"Invalid stepper id\"}"); } return 404; } void ESPStepperMotorServer_RestAPI::handlePostRotaryEncoderRequest(AsyncWebServerRequest *request, uint8_t *data, size_t len, size_t index, size_t total, int encoderIndex) { StaticJsonDocument<300> doc; DeserializationError error = deserializeJson(doc, (const char *)data); if (error) { request->send(400, "application/json", "{\"error\": \"Invalid JSON request, deserialization failed\"}"); ESPStepperMotorServer_Logger::logWarningf("Error while trying to deserialize JSON request: %s", error.c_str()); } else { if (doc.containsKey("stepMultiplier") && doc.containsKey("pinA") && doc.containsKey("pinB") && doc.containsKey("displayName") && doc.containsKey("stepperId")) { const char *displayName = doc["displayName"]; int stepMultiplier = doc["stepMultiplier"]; byte stepperIndex = doc["stepperId"]; byte pinA = doc["pinA"]; byte pinB = doc["pinB"]; if (pinA >= 0 && pinA <= ESPStepperHighestAllowedIoPin && pinB >= 0 && pinB <= ESPStepperHighestAllowedIoPin && pinA != pinB) { ESPStepperMotorServer_RotaryEncoder *encoderToUpdate = this->_stepperMotorServer->getCurrentServerConfiguration()->getRotaryEncoder(encoderIndex); //check if pins are already in use by a stepper, switch or another encoder configuration if (this->_stepperMotorServer->isIoPinUsed(pinA)) { //check if it pin NOT used by same encoder to update if (encoderToUpdate == NULL || encoderToUpdate->getPinAIOPin() != pinA) { AsyncResponseStream *response = request->beginResponseStream("application/json"); response->setCode(400); response->printf("{\"error\": \"The given Pin-A IO pin %i is already used by another stepper, encoder or switch configuration\"}", pinA); request->send(response); return; } } if (this->_stepperMotorServer->isIoPinUsed(pinB)) { //check if it pin NOT used by same encoder to update if (encoderToUpdate == NULL || encoderToUpdate->getPinBIOPin() != pinB) { AsyncResponseStream *response = request->beginResponseStream("application/json"); response->setCode(400); response->printf("{\"error\": \"The given Pin-B IO pin %i is already used by another stepper, encoder or switch configuration\"}", pinB); request->send(response); return; } } ESPStepperMotorServer_RotaryEncoder *encoderToAdd = new ESPStepperMotorServer_RotaryEncoder(pinA, pinB, displayName, stepMultiplier, stepperIndex); if (encoderIndex == -1) { encoderIndex = this->_stepperMotorServer->addOrUpdateRotaryEncoder(encoderToAdd); } else { //"update" existing stepper config which basically means we store it at a specific index encoderIndex = this->_stepperMotorServer->addOrUpdateRotaryEncoder(encoderToAdd, encoderIndex); } AsyncResponseStream *response = request->beginResponseStream("application/json"); response->setCode(200); response->printf("{\"id\": %i}", encoderIndex); request->send(response); return; } else { request->send(400, "application/json", "{\"error\": \"Invalid IO pin number given or Pin A and Pin B are the same\"}"); return; } } else { request->send(400, "application/json", "{\"error\": \"Invalid request, missing one ore more required parameters: stepMultiplier, pinA, pinB, displayName, stepperId\"}"); return; } } } int ESPStepperMotorServer_RestAPI::handleDeleteRotaryEncoderRequest(AsyncWebServerRequest *request, boolean sendResponse) { if (request->hasParam("id")) { int encoderIndex = request->getParam("id")->value().toInt(); if (this->_stepperMotorServer->getCurrentServerConfiguration()->getRotaryEncoder(encoderIndex) != NULL) { this->_stepperMotorServer->removeRotaryEncoder(encoderIndex); if (sendResponse) { request->send(204); } return 204; } } if (sendResponse) { request->send(404, "application/json", "{\"error\": \"Invalid rotary encoder id\"}"); } return 404; } int ESPStepperMotorServer_RestAPI::handleDeleteSwitchRequest(AsyncWebServerRequest *request, boolean sendResponse) { if (request->hasParam("id")) { int switchIndex = request->getParam("id")->value().toInt(); if (this->_stepperMotorServer->getCurrentServerConfiguration()->getSwitch(switchIndex)) { this->_stepperMotorServer->removePositionSwitch(switchIndex); if (sendResponse) { request->send(204); } return 204; } } if (sendResponse) { request->send(404, "application/json", "{\"error\": \"Invalid position switch id\"}"); } return 404; } void ESPStepperMotorServer_RestAPI::handlePostSwitchRequest(AsyncWebServerRequest *request, uint8_t *data, size_t len, size_t index, size_t total, int switchIndex) { StaticJsonDocument<350> doc; DeserializationError error = deserializeJson(doc, (const char *)data); if (error) { request->send(400, "application/json", "{\"error\": \"Invalid JSON request, deserialization failed\"}"); ESPStepperMotorServer_Logger::logWarningf("Error while trying to deserialize JSON request: %s", error.c_str()); } else { if (doc.containsKey("stepperId") && doc.containsKey("ioPinNumber") && doc.containsKey("positionName") && doc.containsKey("switchPosition") && doc.containsKey("switchType")) { int stepperConfigIndex = doc["stepperId"]; byte ioPinNumber = doc["ioPinNumber"]; const char *name = doc["positionName"]; long switchPosition = doc["switchPosition"]; byte switchType = doc["switchType"]; //stepperConfigIndex can be -1 for emergency switch only if (stepperConfigIndex == -1 && !(switchType & (1 << (SWITCHTYPE_EMERGENCY_STOP_SWITCH_BIT - 1)))) { request->send(400, "application/json", "{\"error\": \"Invalid Stepper ID. Only emergency stop switches are allowed to have -1 as stepper configuration reference\"}"); return; } if (ioPinNumber >= 0 && ioPinNumber <= ESPStepperHighestAllowedIoPin) //check valid pin range value { ESPStepperMotorServer_PositionSwitch *switchToUpdate = this->_stepperMotorServer->getCurrentServerConfiguration()->getSwitch(switchIndex); //check if pins are already in use by a stepper, switch or another encoder configuration if (this->_stepperMotorServer->isIoPinUsed(ioPinNumber)) { //check if pin is NOT used by same switch to update if (switchToUpdate == NULL || switchToUpdate->getIoPinNumber() != ioPinNumber) { request->send(400, "application/json", "{\"error\": \"The given IO pin is already used by another element\"}"); return; } } if (stepperConfigIndex > -1 && this->_stepperMotorServer->getCurrentServerConfiguration()->getStepperConfiguration(stepperConfigIndex) == NULL) { request->send(404, "application/json", "{\"error\": \"The given stepper id is invalid\"}"); return; } ESPStepperMotorServer_PositionSwitch *posSwitchToAdd = new ESPStepperMotorServer_PositionSwitch(ioPinNumber, stepperConfigIndex, switchType, name, switchPosition); if (doc[this->_stepperMotorServer->getCurrentServerConfiguration()->JSON_SECTION_NAME_SWITCH_CONFIGURATION_MACROACTIONS]) { JsonArray macroActionsJsonArray = doc[this->_stepperMotorServer->getCurrentServerConfiguration()->JSON_SECTION_NAME_SWITCH_CONFIGURATION_MACROACTIONS].as(); if (macroActionsJsonArray) { for (JsonVariant macroActionJson : macroActionsJsonArray) { posSwitchToAdd->addMacroAction(ESPStepperMotorServer_MacroAction::fromJsonObject(macroActionJson)); } } } switchIndex = this->_stepperMotorServer->addOrUpdatePositionSwitch(posSwitchToAdd, switchIndex); AsyncResponseStream *response = request->beginResponseStream("application/json"); response->setCode(200); response->printf("{\"id\": %i}", switchIndex); request->send(response); } else { request->send(400, "application/json", "{\"error\": \"Invalid IO pin number given\"}"); } } else { request->send(400, "application/json", "{\"error\": \"Invalid request, missing one ore more required parameters: stepperId, ioPinNumber, positionName, switchPosition, switchType\"}"); } } } // -------------------------------------- End -------------------------------------- ================================================ FILE: src/ESPStepperMotorServer_RestAPI.h ================================================ // ****************************************************************** // * * // * Header file for ESPStepperMotorServer_RestAPI.cpp * // * * // * Copyright (c) Paul Kerspe, 2019 * // * * // ****************************************************************** // MIT License // // Copyright (c) 2019 Paul Kerspe // // Permission is hereby granted, free of charge, to any person obtaining a copy // of this software and associated documentation files (the "Software"), to deal // in the Software without restriction, including without limitation the rights // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell // copies of the Software, and to permit persons to whom the Software is furnished // to do so, subject to the following conditions: // // The above copyright notice and this permission notice shall be included in all // copies or substantial portions of the Software. // // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE // SOFTWARE. #ifndef ESPStepperMotorServer_RestAPI_h #define ESPStepperMotorServer_RestAPI_h #include #include #include #include #include #include #include #include //just declare class here for compiler, since we have a circular dependency class ESPStepperMotorServer; class ESPStepperMotorServer_RestAPI { public: ESPStepperMotorServer_RestAPI(ESPStepperMotorServer *stepperMotorServer); /** * register all rest endpoint handlers with the given ESP AsyncWebServer instance reference */ void registerRestEndpoints(AsyncWebServer *server); private: String version; ESPStepperMotorServer_Logger *logger; ESPStepperMotorServer *_stepperMotorServer; void populateStepperDetailsToJsonObject(JsonObject &detailsObjecToPopulate, ESPStepperMotorServer_StepperConfiguration *stepper, int index); void populateSwitchDetailsToJsonObject(JsonObject &detailsObjecToPopulate, ESPStepperMotorServer_PositionSwitch *positionSwitch, int index); void populateRotaryEncoderDetailsToJsonObject(JsonObject &detailsObjecToPopulate, ESPStepperMotorServer_RotaryEncoder *rotaryEncoder, int index); void logDebugRequestUrl(AsyncWebServerRequest *request); //movement related endpoints void handleHomingRequest(AsyncWebServerRequest *request); //for other endpoints see ESPStepperMotorServer_RestAPI.cpp in function registerRestEndpoints // SWITCH CONFIGURATION ENDPOINT HANDLER void handlePostSwitchRequest(AsyncWebServerRequest *request, uint8_t *data, size_t len, size_t index, size_t total, int switchIndex = -1); int handleDeleteSwitchRequest(AsyncWebServerRequest *request, boolean sendReponse); // STEPPER CONFIGURATION ENDPOINT HANDLER void handlePostStepperRequest(AsyncWebServerRequest *request, uint8_t *data, size_t len, size_t index, size_t total, int switchIndex = -1); int handleDeleteStepperRequest(AsyncWebServerRequest *request, boolean sendReponse); // ROTARY ENCODER CONFIGURATION ENDPOINT HANDLER void handlePostRotaryEncoderRequest(AsyncWebServerRequest *request, uint8_t *data, size_t len, size_t index, size_t total, int encoderIndex = -1); int handleDeleteRotaryEncoderRequest(AsyncWebServerRequest *request, boolean sendReponse); }; #endif ================================================ FILE: src/ESPStepperMotorServer_RotaryEncoder.cpp ================================================ // ****************************************************************** // // * // // Header file for ESPStepperMotorServer_RotaryEncoder.cpp * // // * // // Copyright (c) Paul Kerspe, 2019 * // // * // ****************************************************************** // // This is a class to support rotary encoders a input controllers for the ESPStepperMotorServer // // It is based on the work Ben Buxton's Rotary Encodr Library, which was licensed under the following conditions: // Copyright 2011 Ben Buxton.Licenced under the GNU GPL Version 3. Contact : bb @cactii.net // Licenced under the GNU GPL Version 3. Contact: bb@cactii.net // https://github.com/buxtronix/arduino/tree/master/libraries/Rotary // // BEGIN OF BENS COMMENT // A typical mechanical rotary encoder emits a two bit gray code // on 3 output pins. Every step in the output (often accompanied // by a physical 'click') generates a specific sequence of output // codes on the pins. // There are 3 pins used for the rotary encoding - one common and // two 'bit' pins. // The following is the typical sequence of code on the output when // moving from one step to the next: // Position Bit1 Bit2 // ---------------------- // Step1 0 0 // 1/4 1 0 // 1/2 1 1 // 3/4 0 1 // Step2 0 0 // // From this table, we can see that when moving from one 'click' to // the next, there are 4 changes in the output code. // // - From an initial 0 - 0, Bit1 goes high, Bit0 stays low. // - Then both bits are high, halfway through the step. // - Then Bit1 goes low, but Bit2 stays high. // - Finally at the end of the step, both bits return to 0. // // Detecting the direction is easy - the table simply goes in the other // direction (read up instead of down). // // To decode this, we use a simple state machine. Every time the output // code changes, it follows state, until finally a full steps worth of // code is received (in the correct order). At the final 0-0, it returns // a value indicating a step in one direction or the other. // // If an invalid state happens (for example we go from '0-1' straight // to '1-0'), the state machine resets to the start until 0-0 and the // next valid codes occur. // // The biggest advantage of using a state machine over other algorithms // is that this has inherent debounce built in. Other algorithms emit spurious // output with switch bounce, but this one will simply flip between // sub-states until the bounce settles, then continue along the state // machine. // A side effect of debounce is that fast rotations can cause steps to // be skipped. By not requiring debounce, fast rotations can be accurately // measured. // Another advantage is the ability to properly handle bad state, such // as due to EMI, etc. // It is also a lot simpler than others - a static state table and less // than 10 lines of logic. // END OF BENS COMMENT // // I included the sources here to reduce the complexity of setting up the required libraries that need to be installed on top of the ESPSMS Library // by the user in the Arduino UI, since it can not currently deal with automatic dependency management like platformIO. // Ben's code is beautiful in its simplicy and therefore does not create a noticable overhead in the code size of the ESPStepperMotorServer. // // // ESPStepperMotorServer is licensed under the following conditions: // // MIT License // // Copyright (c) 2019 Paul Kerspe // // Permission is hereby granted, free of charge, to any person obtaining a copy // of this software and associated documentation files (the "Software"), to deal // in the Software without restriction, including without limitation the rights // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell // copies of the Software, and to permit persons to whom the Software is furnished // to do so, subject to the following conditions: // // The above copyright notice and this permission notice shall be included in all // copies or substantial portions of the Software. // // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE // SOFTWARE. #include "Arduino.h" #include "ESPStepperMotorServer_Logger.h" #include "ESPStepperMotorServer_RotaryEncoder.h" #include "ESPStepperMotorServer.h" // The below state table has, for each state (row), the new state // to set based on the next encoder output. From left to right in, // the table, the encoder outputs are 00, 01, 10, 11, and the value // in that position is the new state to set. #define R_START 0x0 // NOTE regarind HALF STEP support in the original Rotray Encoder library by BenBuxton: // Half Step support has been removed to reduce complexity // Use the full-step state table (emits a code at 00 only) #define R_CW_FINAL 0x1 #define R_CW_BEGIN 0x2 #define R_CW_NEXT 0x3 #define R_CCW_BEGIN 0x4 #define R_CCW_FINAL 0x5 #define R_CCW_NEXT 0x6 const unsigned char ttable[7][4] = { // R_START {R_START, R_CW_BEGIN, R_CCW_BEGIN, R_START}, // R_CW_FINAL {R_CW_NEXT, R_START, R_CW_FINAL, R_START | DIR_CW}, // R_CW_BEGIN {R_CW_NEXT, R_CW_BEGIN, R_START, R_START}, // R_CW_NEXT {R_CW_NEXT, R_CW_BEGIN, R_CW_FINAL, R_START}, // R_CCW_BEGIN {R_CCW_NEXT, R_START, R_CCW_BEGIN, R_START}, // R_CCW_FINAL {R_CCW_NEXT, R_CCW_FINAL, R_START, R_START | DIR_CCW}, // R_CCW_NEXT {R_CCW_NEXT, R_CCW_FINAL, R_CCW_BEGIN, R_START}, }; ESPStepperMotorServer_RotaryEncoder::ESPStepperMotorServer_RotaryEncoder(char pinA, char pinB, String displayName, int stepMultiplier, byte stepperIndex) { // Assign variables. this->_pinA = pinA; this->_pinB = pinB; this->_displayName = displayName; this->_stepMultiplier = stepMultiplier; this->_stepperIndex = stepperIndex; this->_encoderIndex = -1; // Initialise state. this->_state = R_START; } unsigned char ESPStepperMotorServer_RotaryEncoder::process() { // Grab state of input pins. unsigned char pinstate = (digitalRead(this->_pinB) << 1) | digitalRead(this->_pinA); // Determine new state from the pins and state table. this->_state = ttable[this->_state & 0xf][pinstate]; // Return emit bits, ie the generated event. return this->_state & 0x30; } void ESPStepperMotorServer_RotaryEncoder::setId(byte id) { this->_encoderIndex = id; } byte ESPStepperMotorServer_RotaryEncoder::getId() { return this->_encoderIndex; } unsigned char ESPStepperMotorServer_RotaryEncoder::getPinAIOPin() { return this->_pinA; } unsigned char ESPStepperMotorServer_RotaryEncoder::getPinBIOPin() { return this->_pinB; } void ESPStepperMotorServer_RotaryEncoder::setStepperIndex(byte stepperMotorIndex) { if (stepperMotorIndex > -1 && stepperMotorIndex <= ESPStepperHighestAllowedIoPin) { this->_stepperIndex = stepperMotorIndex; } else { ESPStepperMotorServer_Logger::logWarning("ESPStepperMotorServer_RotaryEncoder::setStepperIndex: Invalid stepper motor index value given, must be within he allowed range of 0 >= value <= ESPStepperHighestAllowedIoPin"); } } byte ESPStepperMotorServer_RotaryEncoder::getStepperIndex() { return this->_stepperIndex; } const String ESPStepperMotorServer_RotaryEncoder::getDisplayName() { return this->_displayName; } void ESPStepperMotorServer_RotaryEncoder::setStepMultiplier(unsigned int stepMultiplier) { this->_stepMultiplier = stepMultiplier; } unsigned int ESPStepperMotorServer_RotaryEncoder::getStepMultiplier() { return this->_stepMultiplier; } ================================================ FILE: src/ESPStepperMotorServer_RotaryEncoder.h ================================================ // ****************************************************************** // * * // * Header file for ESPStepperMotorServer_RotaryEncoder.cpp * // * * // * Copyright (c) Paul Kerspe, 2019 * // * * // ****************************************************************** // // This is a class to support rotary encoders a input controllers for the ESPStepperMotorServer // // It is based on the work Ben Buxton's Rotary Encodr Library, which was licensed under the following conditions: // Copyright 2011 Ben Buxton.Licenced under the GNU GPL Version 3. Contact : bb @cactii.net // Licenced under the GNU GPL Version 3. Contact: bb@cactii.net // https://github.com/buxtronix/arduino/tree/master/libraries/Rotary // // I included the sources here to reduce the complexity of setting up the required libraries that need to be installed on top of the ESPSMS Library // by the user in the Arduino UI, since it can not currently deal with automatic dependency management like platformIO. // Ben's code is beautiful in its simplicy and therefore does not create a noticable overhead in the code size of the ESPStepperMotorServer. // // // ESPStepperMotorServer is licensed under the following conditions: // // MIT License // // Copyright (c) 2019 Paul Kerspe // // Permission is hereby granted, free of charge, to any person obtaining a copy // of this software and associated documentation files (the "Software"), to deal // in the Software without restriction, including without limitation the rights // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell // copies of the Software, and to permit persons to whom the Software is furnished // to do so, subject to the following conditions: // // The above copyright notice and this permission notice shall be included in all // copies or substantial portions of the Software. // // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE // SOFTWARE. #ifndef ESPStepperMotorServer_RotaryEncoder_h #define ESPStepperMotorServer_RotaryEncoder_h #include "Arduino.h" // Enable this to emit codes twice per step. //#define HALF_STEP // Enable weak pullups #define ENABLE_PULLUPS // Values returned by 'process' // No complete step yet. #define DIR_NONE 0x0 // Clockwise step. #define DIR_CW 0x10 // Anti-clockwise step. #define DIR_CCW 0x20 //size calculated using https://arduinojson.org/v6/assistant/ #define RESERVED_JSON_SIZE_ESPStepperMotorServer_RotaryEncoder 170 class ESPStepperMotorServer_RotaryEncoder { friend class ESPStepperMotorServer; public: /** * Constructor for the rotary encoder entity. * The arguments define the PGIO Pins to be used to connect the Rotary encoder to * The displayName defines the human readable name for thi encoder in the User Interface and logs */ ESPStepperMotorServer_RotaryEncoder(char pinA, char pinB, String displayName, int stepMultiplier, byte stepperIndex); /** * setter to set the id of this encoder. * Only use this if you know what you are doing */ void setId(byte id); /** * get the id of the rotary encoder */ byte getId(); /** * process the input states of the io pins to determine the current rotary encoder step status */ unsigned char process(); /** * return the configured GPIO pin number that is connected to pin A of the rotary encoder */ unsigned char getPinAIOPin(); /** * return the configured GPIO pin number that is connected to pin B of the rotary encoder */ unsigned char getPinBIOPin(); /** * get the configured display name of the rotary encoder */ const String getDisplayName(); /** * set the stepper motor id that should be linked to this rotary encoder */ void setStepperIndex(byte stepperMotorIndex); /** * get the configured id of the stepper motor that is linked to this rotary encoder */ byte getStepperIndex(); /** * set a multiplication factor used to calculate the ammount of pulses send to the stepper motor for one step of the rotary encoder. * Default is factor of 1, so if one step in the rotatry encoder will be convertd into on puls to the steppr motor driver. * If microstpping is configured in the stepper driver board, one pulse will be one microstep, so it might be needed to st this multiplier accordingly to the microstepp setting of the stepper drivr board. * e.g. if you configured 32 microsteps in your stepper driver board and you want the stepper motor to perform one full step per rotary encoder step, you need to set this mulitplier to 32 */ void setStepMultiplier(unsigned int stepMultiplier); /** * get the configured step multiplier value for this rotary encoder */ unsigned int getStepMultiplier(void); private: unsigned char _state; unsigned char _pinA; unsigned char _pinB; unsigned char _encoderIndex; byte _stepperIndex; String _displayName; // step multiplier is used to define how many pulses should be sen to the stepper for one step from the rotary encoder unsigned int _stepMultiplier; }; #endif ================================================ FILE: src/ESPStepperMotorServer_StepperConfiguration.cpp ================================================ // ********************************************************************* // * * // * ESP8266 and ESP32 Stepper Motor Server - Stepper Config class * // * a wrapper class to decouple the FlexyStepper class a bit better * // * Copyright (c) Paul Kerspe, 2019 * // * * // ********************************************************************* // // MIT License // // Copyright (c) 2019 Paul Kerspe // // Permission is hereby granted, free of charge, to any person obtaining a copy // of this software and associated documentation files (the "Software"), to deal // in the Software without restriction, including without limitation the rights // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell // copies of the Software, and to permit persons to whom the Software is furnished // to do so, subject to the following conditions: // // The above copyright notice and this permission notice shall be included in all // copies or substantial portions of the Software. // // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE // SOFTWARE. // #include "ESPStepperMotorServer_StepperConfiguration.h" ESPStepperMotorServer_StepperConfiguration::ESPStepperMotorServer_StepperConfiguration(const ESPStepperMotorServer_StepperConfiguration &espStepperConfiguration) { this->_flexyStepper = new ESP_FlexyStepper; *this->_flexyStepper = *espStepperConfiguration._flexyStepper; this->_stepIoPin = espStepperConfiguration._stepIoPin; this->_directionIoPin = espStepperConfiguration._directionIoPin; this->_stepsPerMM = espStepperConfiguration._stepsPerMM; this->_stepsPerRev = espStepperConfiguration._stepsPerRev; this->_microsteppingDivisor = espStepperConfiguration._microsteppingDivisor; this->_displayName = espStepperConfiguration._displayName; this->_rpmLimit = espStepperConfiguration._rpmLimit; this->_flexyStepper->connectToPins(this->_stepIoPin, this->_directionIoPin); } ESPStepperMotorServer_StepperConfiguration::~ESPStepperMotorServer_StepperConfiguration() { delete this->_flexyStepper; } // // constructor for the stepper wrapper class // ESPStepperMotorServer_StepperConfiguration::ESPStepperMotorServer_StepperConfiguration(byte stepIoPin, byte directionIoPin) { this->_stepIoPin = stepIoPin; this->_directionIoPin = directionIoPin; this->_flexyStepper = new ESP_FlexyStepper(); this->_flexyStepper->connectToPins(this->_stepIoPin, this->_directionIoPin); } ESPStepperMotorServer_StepperConfiguration::ESPStepperMotorServer_StepperConfiguration(byte stepIoPin, byte directionIoPin, String displayName, unsigned int stepsPerRev, unsigned int stepsPerMM, unsigned int microsteppingDivisor, unsigned int rpmLimit) { this->_stepIoPin = stepIoPin; this->_directionIoPin = directionIoPin; this->_microsteppingDivisor = microsteppingDivisor; this->_displayName = displayName; this->_rpmLimit = rpmLimit; this->_flexyStepper = new ESP_FlexyStepper(); this->_flexyStepper->connectToPins(this->_stepIoPin, this->_directionIoPin); //we store the value in flexistepper and locally, since flexystepper does not provider getters this->_flexyStepper->setStepsPerMillimeter(stepsPerMM * this->_microsteppingDivisor); this->_stepsPerMM = stepsPerMM; //we store the value in flexistepper and locally, since flexystepper does not provider getters this->_flexyStepper->setStepsPerRevolution(stepsPerRev * this->_microsteppingDivisor); this->_stepsPerRev = stepsPerRev; } // --------------------------------------------------------------------------------- // Getters / Setters // --------------------------------------------------------------------------------- ESP_FlexyStepper *ESPStepperMotorServer_StepperConfiguration::getFlexyStepper() { return this->_flexyStepper; } void ESPStepperMotorServer_StepperConfiguration::setId(byte id) { this->_stepperIndex = id; } byte ESPStepperMotorServer_StepperConfiguration::getId() { return this->_stepperIndex; } String ESPStepperMotorServer_StepperConfiguration::getDisplayName() { return this->_displayName; } void ESPStepperMotorServer_StepperConfiguration::setDisplayName(String displayName) { if (displayName.length() > ESPSMS_Stepper_DisplayName_MaxLength) { char logString[160]; sprintf(logString, "ESPStepperMotorServer_StepperConfiguration::setDisplayName: The display name for stepper with id %i is to long. Max length is %i characters. Name will be trimmed", this->getId(), ESPSMS_Stepper_DisplayName_MaxLength); ESPStepperMotorServer_Logger::logWarning(logString); this->_displayName = displayName.substring(0, ESPSMS_Stepper_DisplayName_MaxLength); } else { this->_displayName = displayName; } } byte ESPStepperMotorServer_StepperConfiguration::getStepIoPin() { return this->_stepIoPin; } byte ESPStepperMotorServer_StepperConfiguration::getDirectionIoPin() { return this->_directionIoPin; } // brake control settings byte ESPStepperMotorServer_StepperConfiguration::getBrakeIoPin() { return this->_brakeIoPin; } long ESPStepperMotorServer_StepperConfiguration::getBrakeEngageDelayMs() { return this->_brakeEngageDelayMs; } long ESPStepperMotorServer_StepperConfiguration::getBrakeReleaseDelayMs() { return this->_brakeReleaseDelayMs; } byte ESPStepperMotorServer_StepperConfiguration::getBrakePinActiveState() { return this->_brakePinActiveState; } void ESPStepperMotorServer_StepperConfiguration::setBrakeIoPin(byte brakeIoPin, byte brakePinActiveState) { this->_brakeIoPin = brakeIoPin; this->_brakePinActiveState = brakePinActiveState; this->_flexyStepper->setBrakePin(brakeIoPin, brakePinActiveState); } void ESPStepperMotorServer_StepperConfiguration::setBrakeEngageDelayMs(long delay) { this->_brakeEngageDelayMs = delay; this->_flexyStepper->setBrakeEngageDelayMs(delay); } void ESPStepperMotorServer_StepperConfiguration::setBrakeReleaseDelayMs(long delay) { this->_brakeReleaseDelayMs = delay; this->_flexyStepper->setBrakeReleaseDelayMs(delay); } void ESPStepperMotorServer_StepperConfiguration::setBrakePinActiveState(byte activeState) { this->_brakePinActiveState = activeState; this->_flexyStepper->setBrakePin(this->_brakeIoPin, this->_brakePinActiveState); } // motion configurateion settings void ESPStepperMotorServer_StepperConfiguration::setStepsPerRev(unsigned int stepsPerRev) { this->_flexyStepper->setStepsPerRevolution(stepsPerRev * this->_microsteppingDivisor); this->_stepsPerRev = stepsPerRev; } unsigned int ESPStepperMotorServer_StepperConfiguration::getStepsPerRev() { return this->_stepsPerRev; } void ESPStepperMotorServer_StepperConfiguration::setStepsPerMM(unsigned int stepsPerMM) { this->_flexyStepper->setStepsPerMillimeter(stepsPerMM * this->_microsteppingDivisor); this->_stepsPerMM = stepsPerMM; } unsigned int ESPStepperMotorServer_StepperConfiguration::getStepsPerMM() { return this->_stepsPerMM; } void ESPStepperMotorServer_StepperConfiguration::setMicrostepsPerStep(unsigned int microstepsPerStep) { //check for power of two value, since others are not allowed in micro step sizes if (microstepsPerStep && !(microstepsPerStep & (microstepsPerStep - 1))) { this->_microsteppingDivisor = microstepsPerStep; //update flexy stepper as well in regards to steps/rev and steps/mm this->_flexyStepper->setStepsPerMillimeter(this->_stepsPerMM * this->_microsteppingDivisor); this->_flexyStepper->setStepsPerRevolution(this->_stepsPerRev * this->_microsteppingDivisor); } else { ESPStepperMotorServer_Logger::logWarningf("Invalid microstepping value given: %i. Only values which are power of two are allowed", microstepsPerStep); } } unsigned int ESPStepperMotorServer_StepperConfiguration::getMicrostepsPerStep() { return this->_microsteppingDivisor; } void ESPStepperMotorServer_StepperConfiguration::setRpmLimit(unsigned int rpmLimit) { if (rpmLimit > ESPSMS_MAX_UPPER_RPM_LMIT) { char logString[170]; sprintf(logString, "ESPStepperMotorServer_StepperConfiguration::setRpmLimit: The given rpm limit value %u exceeds the allowed maximum rpm limit of %i, will set to %i", rpmLimit, ESPSMS_MAX_UPPER_RPM_LMIT, ESPSMS_MAX_UPPER_RPM_LMIT); ESPStepperMotorServer_Logger::logWarning(logString); this->_rpmLimit = ESPSMS_MAX_UPPER_RPM_LMIT; } else { this->_rpmLimit = rpmLimit; } } unsigned int ESPStepperMotorServer_StepperConfiguration::getRpmLimit() { return this->_rpmLimit; } ================================================ FILE: src/ESPStepperMotorServer_StepperConfiguration.h ================================================ // ************************************************************************* // * * // * Header file for ESPStepperMotorServer_StepperConfiguration.cpp * // * * // * Copyright (c) Paul Kerspe, 2019 * // * * // ************************************************************************* // MIT License // // Copyright (c) 2019 Paul Kerspe // // Permission is hereby granted, free of charge, to any person obtaining a copy // of this software and associated documentation files (the "Software"), to deal // in the Software without restriction, including without limitation the rights // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell // copies of the Software, and to permit persons to whom the Software is furnished // to do so, subject to the following conditions: // // The above copyright notice and this permission notice shall be included in all // copies or substantial portions of the Software. // // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE // SOFTWARE. #ifndef ESPStepperMotorServer_StepperConfiguration_h #define ESPStepperMotorServer_StepperConfiguration_h #include #include #define ESPSMS_MICROSTEPS_OFF 1 #define ESPSMS_MICROSTEPS_2 2 #define ESPSMS_MICROSTEPS_4 4 #define ESPSMS_MICROSTEPS_8 8 #define ESPSMS_MICROSTEPS_16 16 #define ESPSMS_MICROSTEPS_32 32 #define ESPSMS_MICROSTEPS_128 128 #define ESPSMS_MICROSTEPS_256 256 #define ESPSMS_MAX_UPPER_RPM_LMIT 3000 #define ESPSMS_Stepper_DisplayName_MaxLength 20 //size calculated using https://arduinojson.org/v6/assistant/ #define RESERVED_JSON_SIZE_ESPStepperMotorServer_StepperConfiguration 210 class ESPStepperMotorServer_StepperConfiguration { friend class ESPStepperMotorServer; public: ESPStepperMotorServer_StepperConfiguration(const ESPStepperMotorServer_StepperConfiguration &espStepperConfiguration); ~ESPStepperMotorServer_StepperConfiguration(); ESPStepperMotorServer_StepperConfiguration(byte stepIoPin, byte directionIoPin); ESPStepperMotorServer_StepperConfiguration(byte stepIoPin, byte directionIoPin, String displayName, unsigned int stepsPerRev, unsigned int stepsPerMM, unsigned int microsteppingDivisor, unsigned int rpmLimit); ESP_FlexyStepper *getFlexyStepper(); /** * Internally used setter to set the id of this stepper motor. * Only use this if you know what you are doing */ void setId(byte id); /** * get the internal id of this stepper motor configuration within the stepper server */ byte getId(); /** * Set the display name of the stepper motor to be shown in the user intefaces */ void setDisplayName(String displayName); /** * Get the currently configured display name for the stepper motor */ String getDisplayName(); /** * Get the currently configured IO pin that is used to send step pulses to the stepper driver */ byte getStepIoPin(); /** * Get the currently configured IO pin that is used to send the direction signal to the stepper driver */ byte getDirectionIoPin(); /** * Get the currently configured IO pin that is used to engage an optional engine/motor brake. * Returns ESPServerStepperUnsetIoPinNumber (255) if none is defined */ byte getBrakeIoPin(); /** * Get the currently configured active state of the IO pin used to enabel the engine/motor brake. * Returns 1 for active high (pin goes high to activate the brake), 2 for active low (pin goes low to activate the brake) */ byte getBrakePinActiveState(); /** * Get the currently configured delay in ms between the motor comes to a stop and the engine brake is being engaged. Default is 0ms. */ long getBrakeEngageDelayMs(); /** * Get the currently confgured timeout of inactivity of the motor, before the motor brake is released. * Default is -1, meaning that the brake is never released as long as the engine is stopped. */ long getBrakeReleaseDelayMs(); void setBrakeIoPin(byte, byte); void setBrakePinActiveState(byte); void setBrakeEngageDelayMs(long); void setBrakeReleaseDelayMs(long); /** * Set the number of full steps the stepper motor itself needs to perform for a full revolution. * Most stepper motors perform 1.8 degree turn per step, thus resulting in 200 full steps per revolution. * Other somewhat common values are 3.6 degreee (100 steps/rev), 3.75 degree (96 steps/rev) and 7.5 degree (48 steps/rev) per full step. * Geared stepper motors may have much smaller values, resutling in a much higher steps/rev value. See the datasheet of your stepper motor for the correct value. * The default value is 200 steps/rev since this is the most common value. */ void setStepsPerRev(unsigned int); /** * Get the currently configured steps/rev value for this steppe motor * The default value is 200 steps/rev **/ unsigned int getStepsPerRev(); /** * Set the number of full steps (not microsteps!) required to move the axis by 1mm. * This depends on the lead screw pitch (if lead screws are used) or the gear ratio or whatever mechanism is used to transform revolutions of the stepper motor to linear motion * The default value is 100 steps/rev since this is the most common value for T8 leadscrews in regards to pitch. */ void setStepsPerMM(unsigned int); /** * Get the currently configured steps/mm value for this steppe motor * The default value is 100 steps/mm since standard T8 lead screws have a pitch of 2mm per rev, this, combined with the standard 200steps/rev of stepper motors, leads to 100 steps/mm **/ unsigned int getStepsPerMM(); /** * Set the number of microsteps you configured in the stepper driver (usually one with DIP switches on the driver board) for this stepper motor. * Common values are 1 (no micro stepping), 2 (half step), 4, 8, 16, 32, 64, 128 and sometimes 256 microsteps per step. * This setting is needed to calculate the proper amount of pulses that need to be send to the stepper driver. * If this value does not match the configured micro step setting on your driver board, * the number of pulses need to travel a certain distance in mm or to perform a certain amount of revolutions with the stepper motor, will not be correct. * The default value is 1 (ESPSMS_MICROSTEPS_OFF). * Allowed values: ESPSMS_MICROSTEPS_OFF (full stepping), ESPSMS_MICROSTEPS_2 (half stepping), ESPSMS_MICROSTEPS_4, ESPSMS_MICROSTEPS_8, ESPSMS_MICROSTEPS_16, ESPSMS_MICROSTEPS_32, ESPSMS_MICROSTEPS_64, ESPSMS_MICROSTEPS_128, ESPSMS_MICROSTEPS_256 */ void setMicrostepsPerStep(unsigned int); /** * Get the currently configured number of microsteps per step for this stepper motor. * The default value is 1 (ESPSMS_MICROSTEPS_OFF) **/ unsigned int getMicrostepsPerStep(); /** * Set the maximum revolutions per minute for this stepper. * This limit will only be used to limit the allowed values in the rest api enpoints / user interfaces and to calculate the maximum step pulse frequncy needed. * If the step pulse frequnency is higher than the one your motor can handle, you might lose steps or the motor might stall. * See your stepper motors datasheet for the torque curve an chose the limit that fits your needs (some datasheets specify the PPS (=Pulses per second) rather then revs/minutem, so make sure you get the right unit when settings this value). * The default setting is 1200 revs/minute, which might be already to high for some steppers (especially geared ones or steppers driven with a low voltage) **/ void setRpmLimit(unsigned int); /** * Get the currently configured Revolutions per Minute limit for this stepper. * Default is 1200 revs/minute. */ unsigned int getRpmLimit(); const static byte ESPServerStepperUnsetIoPinNumber = 255; private: // // private member variables // ESP_FlexyStepper *_flexyStepper; String _displayName; byte _stepperIndex = 0; byte _stepIoPin = ESPServerStepperUnsetIoPinNumber; byte _directionIoPin = ESPServerStepperUnsetIoPinNumber; byte _brakeIoPin = ESPServerStepperUnsetIoPinNumber; byte _brakePinActiveState = 1; // 1 = active high, 2 = active low long _brakeEngageDelayMs = 0; long _brakeReleaseDelayMs = -1; unsigned int _stepsPerRev = 200; unsigned int _stepsPerMM = 100; unsigned int _microsteppingDivisor = ESPSMS_MICROSTEPS_OFF; unsigned int _rpmLimit = 1200; }; // ------------------------------------ End --------------------------------- #endif ================================================ FILE: src/ESPStepperMotorServer_WebInterface.cpp ================================================ // ********************************************************* // * * // * ESP32 Stepper Motor Web Interface * // * * // * Copyright (c) Paul Kerspe, 2019 * // * * // ********************************************************** // MIT License // // Copyright (c) 2019 Paul Kerspe // // Permission is hereby granted, free of charge, to any person obtaining a copy // of this software and associated documentation files (the "Software"), to deal // in the Software without restriction, including without limitation the rights // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell // copies of the Software, and to permit persons to whom the Software is furnished // to do so, subject to the following conditions: // // The above copyright notice and this permission notice shall be included in all // copies or substantial portions of the Software. // // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE // SOFTWARE. #include HTTPClient http; // --------------------------------------------------------------------------------- // Setup functions // --------------------------------------------------------------------------------- // // constructor for the web user interface module // ESPStepperMotorServer_WebInterface::ESPStepperMotorServer_WebInterface(ESPStepperMotorServer *serverRef) { this->_serverRef = serverRef; this->_httpServer = NULL; } /** * check if the UI files exist in the SPIFFS and then register all endpoints for the web UI in the http server */ void ESPStepperMotorServer_WebInterface::registerWebInterfaceUrls(AsyncWebServer *httpServer) { this->_httpServer = httpServer; //OTA update form this->_httpServer->on("/update", HTTP_GET, [this](AsyncWebServerRequest *request) { if (LittleFS.exists(this->webUiFirmwareUpdate)) { AsyncWebServerResponse *response = request->beginResponse(LittleFS, this->webUiFirmwareUpdate, "text/html"); response->addHeader("Content-Encoding", "gzip"); request->send(response); } else { request->send(200, "text/html", "

Firmware update

Firmware File:

"); } }); //OTA Update handler this->_httpServer->on( "/update", HTTP_POST, [this](AsyncWebServerRequest *request) { // the request handler is triggered after the upload has finished... AsyncWebServerResponse *response = request->beginResponse(200, "text/plain", (Update.hasError())?"UPDATE FAILED":"SUCCESS. Rebooting server now"); response->addHeader("Connection", "close"); response->addHeader("Access-Control-Allow-Origin", "*"); request->send(response); if (!Update.hasError()) { delay(100); this->_serverRef->requestReboot("Firmware update completed"); } }, //Upload handler to process chunks of data [](AsyncWebServerRequest *request, String filename, size_t index, uint8_t *data, size_t len, bool final) { if (!filename.endsWith(".bin")) { Serial.println("Invalid firmware file provided, must have .bin-extension"); request->send(400, "text/plain", "Invalid fimrware file given"); request->client()->close(); } else { if (!index) { // if index == 0 then this is the first frame of data Serial.printf("UploadStart: %s\n", filename.c_str()); Serial.setDebugOutput(true); // calculate sketch space required for the update uint32_t maxSketchSpace = (ESP.getFreeSketchSpace() - 0x1000) & 0xFFFFF000; if (!Update.begin(maxSketchSpace)) { //start with max available size Update.printError(Serial); } } //Write chunked data to the free sketch space if (Update.write(data, len) != len) { Update.printError(Serial); } if (final) { // if the final flag is set then this is the last frame of data if (Update.end(true)) { //true to set the size to the current progress Serial.printf("Update Success: %u B\nRebooting...\n", index + len); } else { Update.printError(Serial); } Serial.setDebugOutput(false); } } }); if (this->_serverRef->isSPIFFSMounted() && checkIfGuiExistsInSpiffs()) { this->_httpServer->on("/", HTTP_GET, [this](AsyncWebServerRequest *request) { request->send(LittleFS, this->webUiIndexFile); }); this->_httpServer->on(this->webUiIndexFile, HTTP_GET, [this](AsyncWebServerRequest *request) { request->send(LittleFS, this->webUiIndexFile); }); this->_httpServer->on(this->webUiFaviconFile, HTTP_GET, [this](AsyncWebServerRequest *request) { AsyncWebServerResponse *response = request->beginResponse(LittleFS, this->webUiFaviconFile, "image/x-icon"); //response->addHeader("Content-Encoding", "gzip"); request->send(response); }); /* REMOVED FOR NOW DUE TO SECURITY ISSUES. CAN STILL USE /api/config endpoint to download config (in memory config though!) this->_httpServer->on(this->_serverRef->defaultConfigurationFilename, HTTP_GET, [this](AsyncWebServerRequest *request) { //FIME: currently this streams the json config including the WiFi Credentials, which might be a security risk. //TODO: replace wifi passwords in config with placeholder (maybe add config flag to API to allowed disabling the security feature in the future) AsyncWebServerResponse *response = request->beginResponse(LittleFS, this->_serverRef->defaultConfigurationFilename, "application/json", true); request->send(response); }); */ this->_httpServer->on("/js/app.js", HTTP_GET, [this](AsyncWebServerRequest *request) { request->redirect(this->webUiJsFile); }); this->_httpServer->on(this->webUiJsFile, HTTP_GET, [this](AsyncWebServerRequest *request) { AsyncWebServerResponse *response = request->beginResponse(LittleFS, this->webUiJsFile, "text/javascript"); response->addHeader("Content-Encoding", "gzip"); request->send(response); }); //little test page to show contents of SPIFFS and check if it is initialized at all for trouble shooting this->_httpServer->on("/selftest", HTTP_GET, [this](AsyncWebServerRequest *request) { AsyncResponseStream *response = request->beginResponseStream("text/html"); response->print("ESP-StepperMotorServer Test Page"); response->print("

ESP-StepperMotorServer self test

Testing environment:

    "); response->printf("
  • Server Version: %s", this->_serverRef->version); response->printf("
  • LittleFS Initialized: %s
  • ", (this->_serverRef->isSPIFFSMounted()) ? "true" : "false"); if (!this->_serverRef->isSPIFFSMounted()) { response->print("ERROR: LittleFS not initialized & mounted, in case you are intending to use the WEB UI, you need to make sure the LittleFS Filesystem has been properly initialized on your ESP32"); } else { response->printf("
  • WEB UI installed completely: %s
  • ", (this->checkIfGuiExistsInSpiffs()) ? "true" : "false"); File root = LittleFS.open("/"); if (!root) { response->print("ERROR: Failed to open root folder on LittleFS for reading"); } if (root.isDirectory()) { response->print("
  • Listing files in root folder of LittleFS:
      "); File file = root.openNextFile(); while (file) { response->printf("
    • File: %s (%i) %ld
    • ", file.name(), file.size(), file.getLastWrite()); file = root.openNextFile(); } response->printf("
  • "); root.close(); } } response->printf("
"); String output = String(""); this->_serverRef->getServerStatusAsJsonString(output); //populate string with json response->print(output); response->print("
"); //send the response last request->send(response); }); // register image paths with caching header present this->_httpServer->on(this->webUiLogoFile, HTTP_GET, [this](AsyncWebServerRequest *request) { AsyncWebServerResponse *response = request->beginResponse(LittleFS, this->webUiLogoFile, "image/svg+xml"); response->addHeader("Cache-Control", "max-age=36000, public"); request->send(response); }); this->_httpServer->on(this->webUiStepperGraphic, HTTP_GET, [this](AsyncWebServerRequest *request) { AsyncWebServerResponse *response = request->beginResponse(LittleFS, this->webUiStepperGraphic, "image/svg+xml"); response->addHeader("Cache-Control", "max-age=36000, public"); request->send(response); }); this->_httpServer->on(this->webUiEncoderGraphic, HTTP_GET, [this](AsyncWebServerRequest *request) { AsyncWebServerResponse *response = request->beginResponse(LittleFS, this->webUiEncoderGraphic, "image/svg+xml"); response->addHeader("Cache-Control", "max-age=36000, public"); request->send(response); }); this->_httpServer->on(this->webUiEmergencySwitchGraphic, HTTP_GET, [this](AsyncWebServerRequest *request) { AsyncWebServerResponse *response = request->beginResponse(LittleFS, this->webUiEmergencySwitchGraphic, "image/svg+xml"); response->addHeader("Cache-Control", "max-age=36000, public"); request->send(response); }); this->_httpServer->on(this->webUiSwitchGraphic, HTTP_GET, [this](AsyncWebServerRequest *request) { AsyncWebServerResponse *response = request->beginResponse(LittleFS, this->webUiSwitchGraphic, "image/svg+xml"); response->addHeader("Cache-Control", "max-age=36000, public"); request->send(response); }); this->_httpServer->onNotFound([this](AsyncWebServerRequest *request) { request->send(404, "text/html", "

ESP-StepperMotor-Server

The requested file could not be found"); }); } else { ESPStepperMotorServer_Logger::logInfo("No web UI could be registered"); } } /** * Checks if all required UI files exist in the SPIFFS. * Will try to download the current version of the files from the git hub repo if they could not be found */ bool ESPStepperMotorServer_WebInterface::checkIfGuiExistsInSpiffs() { #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG ESPStepperMotorServer_Logger::logDebug("Checking if web UI is installed in SPIFFS"); #endif if (!this->_serverRef->isSPIFFSMounted()) { ESPStepperMotorServer_Logger::logWarning("LittleFS is not mounted, UI files not found"); return false; } else { bool uiComplete = true; const char *notPresent = "The file %s could not be found on LittleFS\n"; const char *files[] = { this->webUiIndexFile, this->webUiJsFile, this->webUiLogoFile, this->webUiFaviconFile, this->webUiEncoderGraphic, this->webUiEmergencySwitchGraphic, this->webUiStepperGraphic, this->webUiSwitchGraphic, this->webUiFirmwareUpdate}; for (int i = 0; i < 9; i++) //ALWAYS UPDATE THIS COUNTER IF NEW FILES ARE ADDED TO UI { if (!LittleFS.exists(files[i])) { ESPStepperMotorServer_Logger::logInfof(notPresent, files[i]); if (this->_serverRef->getCurrentServerConfiguration()->wifiMode == ESPServerWifiModeClient && WiFi.isConnected()) { char downloadUrl[200]; strcpy(downloadUrl, webUiRepositoryBasePath); strcat(downloadUrl, files[i]); if (!this->downloadFileToSpiffs(downloadUrl, files[i])) { uiComplete = false; } } else { uiComplete = false; } } } if (uiComplete == false && this->_serverRef->getCurrentServerConfiguration()->wifiMode == ESPServerWifiModeAccessPoint) { ESPStepperMotorServer_Logger::logWarning("The UI does not seem to be installed completely on SPIFFS. Automatic download failed since the server is in Access Point mode and not connected to the internet"); ESPStepperMotorServer_Logger::logWarning("Start the server in wifi client (STA) mode to enable automatic download of the web interface files to SPIFFS"); } #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG else if (ESPStepperMotorServer_Logger::isDebugEnabled()) { if (uiComplete == true) { ESPStepperMotorServer_Logger::logDebug("Check completed successfully"); } else { ESPStepperMotorServer_Logger::logDebug("Check failed, one or more UI files are missing and could not be downloaded automatically"); } } #endif return uiComplete; } } // Perform an HTTP GET request to a remote page to download a file to LittleFS bool ESPStepperMotorServer_WebInterface::downloadFileToSpiffs(const char *url, const char *targetPath) { if (!this->_serverRef->isSPIFFSMounted()) { ESPStepperMotorServer_Logger::logWarningf("downloading of %s was canceled since LittleFS is not mounted\n"); return false; } else { #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG ESPStepperMotorServer_Logger::logDebugf("downloading %s from %s\n", targetPath, url); #endif if (http.begin(url)) { #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG int httpCode = http.GET(); ESPStepperMotorServer_Logger::logDebugf("server responded with %i\n", httpCode); #endif ////////////////// // get length of document (is -1 when Server sends no Content-Length header) int len = http.getSize(); uint8_t buff[128] = {0}; #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG ESPStepperMotorServer_Logger::logDebugf("starting download stream for file size %i\n", len); #endif WiFiClient *stream = &http.getStream(); #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG ESPStepperMotorServer_Logger::logDebug("opening file for writing"); #endif File f = LittleFS.open(targetPath, "w+"); // read all data from server while (http.connected() && (len > 0 || len == -1)) { // get available data size size_t size = stream->available(); #ifndef ESPStepperMotorServer_COMPILE_NO_DEBUG ESPStepperMotorServer_Logger::logDebugf("%i bytes available to read from stream\n", size); #endif if (size) { // read up to 128 byte int c = stream->readBytes(buff, ((size > sizeof(buff)) ? sizeof(buff) : size)); // write it to file for (int i = 0; i < c; i++) { f.write(buff[i]); } if (len > 0) { len -= c; } } delay(1); } f.close(); ESPStepperMotorServer_Logger::logInfof("Download of %s completed\n", targetPath); http.end(); //Close connection } return LittleFS.exists(targetPath); } } // -------------------------------------- End -------------------------------------- ================================================ FILE: src/ESPStepperMotorServer_WebInterface.h ================================================ // ****************************************************************** // * * // * Header file for ESPStepperMotorServer_WebInterface.cpp * // * * // * Copyright (c) Paul Kerspe, 2019 * // * * // ****************************************************************** // MIT License // // Copyright (c) 2019 Paul Kerspe // // Permission is hereby granted, free of charge, to any person obtaining a copy // of this software and associated documentation files (the "Software"), to deal // in the Software without restriction, including without limitation the rights // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell // copies of the Software, and to permit persons to whom the Software is furnished // to do so, subject to the following conditions: // // The above copyright notice and this permission notice shall be included in all // copies or substantial portions of the Software. // // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE // SOFTWARE. #ifndef ESPStepperMotorServer_WebInterface_h #define ESPStepperMotorServer_WebInterface_h #include #include #include #include #include #include #include //need this forward declaration here due to circular dependency (use in constructor) class ESPStepperMotorServer; class ESPStepperMotorServer_WebInterface { public: ESPStepperMotorServer_WebInterface(ESPStepperMotorServer *serverRef); void registerWebInterfaceUrls(AsyncWebServer *httpServer); private: bool downloadFileToSpiffs(const char *url, const char *targetPath); bool checkIfGuiExistsInSpiffs(); const char *webUiFirmwareUpdate = "/upload.html.gz"; const char *webUiIndexFile = "/index.html"; const char *webUiJsFile = "/js/app.js.gz"; const char *webUiLogoFile = "/img/logo.svg"; const char *webUiEncoderGraphic = "/img/rotaryEncoderWheel.svg"; const char *webUiEmergencySwitchGraphic = "/img/emergencyStopSwitch.svg"; const char *webUiStepperGraphic = "/img/stepper.svg"; const char *webUiSwitchGraphic = "/img/switch.svg"; const char *webUiFaviconFile = "/favicon.ico"; const char *webUiRepositoryBasePath = "https://raw.githubusercontent.com/pkerspe/ESP-StepperMotor-Server-UI/master/data"; ESPStepperMotorServer *_serverRef; AsyncWebServer *_httpServer; }; #endif ================================================ FILE: src/main.cpp ================================================ // ****************************************************************** // * Simple example for starting the stepper motor server * // * Paul Kerspe 31.5.2020 * // ****************************************************************** // // This is the simplest example of how to start the ESP Stepper Motor Server with the Webinterface to perform all setup steps via the Web UI // // This library requires that your stepper motor be connected to the ESP32 // using an external driver that has a "Step and Direction" interface. // // For all driver boards, it is VERY important that you set the motor // current before running the example. This is typically done by adjusting // a potentiometer on the board or using dip switches. // Read the driver board's documentation to learn how to configure the driver // // all you need to do, to get started with this example, is fill in your wifi credentials in lines 26/27, then compile and upload to your ESP32. // In order to use the Web Interface of the server, you need to upload the contents of the "data" folder in this example to the LittleFS of your ESP32 // // for a detailed manual on how to use this library please visit: https://github.com/pkerspe/ESP-StepperMotor-Server/blob/master/README.md // *********************************************************************** #include #include ESPStepperMotorServer *stepperMotorServer; const char *wifiName= ""; // enter the SSID of the wifi network to connect to const char *wifiSecret = ""; // enter the password of the the existing wifi network here void setup() { // start the serial interface with 115200 baud // IMPORTANT: the following line is important, since the server relies on the serial console for log output // Do not remove this line! (you can modify the baud rate to your needs though, but keep in mind, that slower baud rates might cause timing issues especially if you set the log level to DEBUG) Serial.begin(115200); // now create a new ESPStepperMotorServer instance (this must be done AFTER the Serial interface has been started) // In this example We create the server instance with all modules activated and log level set to INFO (which is the default, you can also use ESPServerLogLevel_DEBUG to set it to debug instead) stepperMotorServer = new ESPStepperMotorServer(ESPServerRestApiEnabled | ESPServerWebserverEnabled | ESPServerSerialEnabled, ESPServerLogLevel_INFO); // connect to an existing WiFi network. Make sure you set the vairables wifiName and wifiSecret to match you SSID and wifi pasword (see above before the setup function) stepperMotorServer->setWifiCredentials(wifiName, wifiSecret); stepperMotorServer->setWifiMode(ESPServerWifiModeClient); //start the server as a wifi client (DHCP client of an existing wifi network) // NOTE: if you want to start the server in a stand alone mode that opens a wifi access point, then comment out the above two lines and uncomment the following line // stepperMotorServer->setWifiMode(ESPServerWifiModeAccessPoint); // you can define the AP name and the password using the following two lines, otherwise the defaults will be used (Name: ESP-StepperMotor-Server, password: Aa123456) // stepperMotorServer->setAccessPointName(""); // stepperMotorServer->setAccessPointPassword(""); //start the server stepperMotorServer->start(); // the server will now connect to the wifi and start the webserver, rest API and serial command line interface. // check the serial console for more details like the URL of the WebInterface } void loop() { //put your code here }