diff --git a/.github/workflows/arduino_lint.yml b/.github/workflows/arduino_lint.yml index 0e285da2..061e2240 100644 --- a/.github/workflows/arduino_lint.yml +++ b/.github/workflows/arduino_lint.yml @@ -3,7 +3,7 @@ jobs: lint: runs-on: ubuntu-latest steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 - uses: arduino/arduino-lint-action@v1 with: library-manager: update diff --git a/.github/workflows/build_examples_atmega2560.yml b/.github/workflows/build_examples_atmega2560.yml index cce882dc..a83027ae 100644 --- a/.github/workflows/build_examples_atmega2560.yml +++ b/.github/workflows/build_examples_atmega2560.yml @@ -13,7 +13,7 @@ jobs: steps: - name: Checkout - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Make directories run: bash extras/scripts/build-pio-dirs.sh - name: Build on PlatformIO diff --git a/.github/workflows/build_examples_atmega32u4.yml b/.github/workflows/build_examples_atmega32u4.yml index cb6c3ba3..db651ec5 100644 --- a/.github/workflows/build_examples_atmega32u4.yml +++ b/.github/workflows/build_examples_atmega32u4.yml @@ -13,7 +13,7 @@ jobs: steps: - name: Checkout - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Make directories run: bash extras/scripts/build-pio-dirs.sh - name: Build on PlatformIO diff --git a/.github/workflows/build_examples_atmelsam.yml b/.github/workflows/build_examples_atmelsam.yml index 335815e8..551a1f3b 100644 --- a/.github/workflows/build_examples_atmelsam.yml +++ b/.github/workflows/build_examples_atmelsam.yml @@ -13,7 +13,7 @@ jobs: steps: - name: Checkout - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Make directories run: bash extras/scripts/build-pio-dirs.sh - name: Build on PlatformIO diff --git a/.github/workflows/build_examples_esp32.yml b/.github/workflows/build_examples_esp32_V3_5_0.yml similarity index 66% rename from .github/workflows/build_examples_esp32.yml rename to .github/workflows/build_examples_esp32_V3_5_0.yml index dbd57243..05f1d4b6 100644 --- a/.github/workflows/build_examples_esp32.yml +++ b/.github/workflows/build_examples_esp32_V3_5_0.yml @@ -1,4 +1,5 @@ -name: Build examples for esp32arduino @ latest + +name: Build examples for esp32 @ V3_5_0 on: push: @@ -13,9 +14,8 @@ jobs: steps: - name: Checkout - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Make directories run: bash extras/scripts/build-pio-dirs.sh - name: Build on PlatformIO - run: bash extras/scripts/build-platformio.sh esp32 - + run: bash extras/scripts/build-platformio.sh esp32_V3_5_0 diff --git a/.github/workflows/build_examples_esp32s3.yml b/.github/workflows/build_examples_esp32_V4_1_0.yml similarity index 65% rename from .github/workflows/build_examples_esp32s3.yml rename to .github/workflows/build_examples_esp32_V4_1_0.yml index 3afb9429..53f08270 100644 --- a/.github/workflows/build_examples_esp32s3.yml +++ b/.github/workflows/build_examples_esp32_V4_1_0.yml @@ -1,4 +1,5 @@ -name: Build examples for esp32s3arduino @ latest + +name: Build examples for esp32 @ V4_1_0 on: push: @@ -13,9 +14,8 @@ jobs: steps: - name: Checkout - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Make directories run: bash extras/scripts/build-pio-dirs.sh - name: Build on PlatformIO - run: bash extras/scripts/build-platformio.sh esp32s3 - + run: bash extras/scripts/build-platformio.sh esp32_V4_1_0 diff --git a/.github/workflows/build_examples_esp32s2.yml b/.github/workflows/build_examples_esp32_V4_2_0.yml similarity index 65% rename from .github/workflows/build_examples_esp32s2.yml rename to .github/workflows/build_examples_esp32_V4_2_0.yml index 4b066209..866ce092 100644 --- a/.github/workflows/build_examples_esp32s2.yml +++ b/.github/workflows/build_examples_esp32_V4_2_0.yml @@ -1,4 +1,5 @@ -name: Build examples for esp32s2arduino @ latest + +name: Build examples for esp32 @ V4_2_0 on: push: @@ -13,9 +14,8 @@ jobs: steps: - name: Checkout - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Make directories run: bash extras/scripts/build-pio-dirs.sh - name: Build on PlatformIO - run: bash extras/scripts/build-platformio.sh esp32s2 - + run: bash extras/scripts/build-platformio.sh esp32_V4_2_0 diff --git a/.github/workflows/build_examples_esp32arduinoV340.yml b/.github/workflows/build_examples_esp32_V4_3_0.yml similarity index 64% rename from .github/workflows/build_examples_esp32arduinoV340.yml rename to .github/workflows/build_examples_esp32_V4_3_0.yml index 1fa02a69..e782d357 100644 --- a/.github/workflows/build_examples_esp32arduinoV340.yml +++ b/.github/workflows/build_examples_esp32_V4_3_0.yml @@ -1,4 +1,5 @@ -name: Build examples for esp32arduino @ 3.4.0 + +name: Build examples for esp32 @ V4_3_0 on: push: @@ -13,9 +14,8 @@ jobs: steps: - name: Checkout - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Make directories run: bash extras/scripts/build-pio-dirs.sh - name: Build on PlatformIO - run: bash extras/scripts/build-platformio.sh esp32arduinoV340 - + run: bash extras/scripts/build-platformio.sh esp32_V4_3_0 diff --git a/.github/workflows/build_examples_esp32_V4_4_0.yml b/.github/workflows/build_examples_esp32_V4_4_0.yml new file mode 100644 index 00000000..f718a697 --- /dev/null +++ b/.github/workflows/build_examples_esp32_V4_4_0.yml @@ -0,0 +1,21 @@ + +name: Build examples for esp32 @ V4_4_0 + +on: + push: + branches: [ master ] + pull_request: + branches: [ master ] + +jobs: + build: + + runs-on: ubuntu-latest + + steps: + - name: Checkout + uses: actions/checkout@v4 + - name: Make directories + run: bash extras/scripts/build-pio-dirs.sh + - name: Build on PlatformIO + run: bash extras/scripts/build-platformio.sh esp32_V4_4_0 diff --git a/.github/workflows/build_examples_esp32_V5_0_0.yml b/.github/workflows/build_examples_esp32_V5_0_0.yml new file mode 100644 index 00000000..2e5fea1c --- /dev/null +++ b/.github/workflows/build_examples_esp32_V5_0_0.yml @@ -0,0 +1,21 @@ + +name: Build examples for esp32 @ V5_0_0 + +on: + push: + branches: [ master ] + pull_request: + branches: [ master ] + +jobs: + build: + + runs-on: ubuntu-latest + + steps: + - name: Checkout + uses: actions/checkout@v4 + - name: Make directories + run: bash extras/scripts/build-pio-dirs.sh + - name: Build on PlatformIO + run: bash extras/scripts/build-platformio.sh esp32_V5_0_0 diff --git a/.github/workflows/build_examples_esp32_V5_1_1.yml b/.github/workflows/build_examples_esp32_V5_1_1.yml new file mode 100644 index 00000000..43ea4ac1 --- /dev/null +++ b/.github/workflows/build_examples_esp32_V5_1_1.yml @@ -0,0 +1,21 @@ + +name: Build examples for esp32 @ V5_1_1 + +on: + push: + branches: [ master ] + pull_request: + branches: [ master ] + +jobs: + build: + + runs-on: ubuntu-latest + + steps: + - name: Checkout + uses: actions/checkout@v4 + - name: Make directories + run: bash extras/scripts/build-pio-dirs.sh + - name: Build on PlatformIO + run: bash extras/scripts/build-platformio.sh esp32_V5_1_1 diff --git a/.github/workflows/build_examples_esp32_V5_2_0.yml b/.github/workflows/build_examples_esp32_V5_2_0.yml new file mode 100644 index 00000000..037d2c7a --- /dev/null +++ b/.github/workflows/build_examples_esp32_V5_2_0.yml @@ -0,0 +1,21 @@ + +name: Build examples for esp32 @ V5_2_0 + +on: + push: + branches: [ master ] + pull_request: + branches: [ master ] + +jobs: + build: + + runs-on: ubuntu-latest + + steps: + - name: Checkout + uses: actions/checkout@v4 + - name: Make directories + run: bash extras/scripts/build-pio-dirs.sh + - name: Build on PlatformIO + run: bash extras/scripts/build-platformio.sh esp32_V5_2_0 diff --git a/.github/workflows/build_examples_esp32_V5_3_0.yml b/.github/workflows/build_examples_esp32_V5_3_0.yml new file mode 100644 index 00000000..daabf976 --- /dev/null +++ b/.github/workflows/build_examples_esp32_V5_3_0.yml @@ -0,0 +1,21 @@ + +name: Build examples for esp32 @ V5_3_0 + +on: + push: + branches: [ master ] + pull_request: + branches: [ master ] + +jobs: + build: + + runs-on: ubuntu-latest + + steps: + - name: Checkout + uses: actions/checkout@v4 + - name: Make directories + run: bash extras/scripts/build-pio-dirs.sh + - name: Build on PlatformIO + run: bash extras/scripts/build-platformio.sh esp32_V5_3_0 diff --git a/.github/workflows/build_examples_esp32_V6_0_1.yml b/.github/workflows/build_examples_esp32_V6_0_1.yml new file mode 100644 index 00000000..b598c90b --- /dev/null +++ b/.github/workflows/build_examples_esp32_V6_0_1.yml @@ -0,0 +1,21 @@ + +name: Build examples for esp32 @ V6_0_1 + +on: + push: + branches: [ master ] + pull_request: + branches: [ master ] + +jobs: + build: + + runs-on: ubuntu-latest + + steps: + - name: Checkout + uses: actions/checkout@v4 + - name: Make directories + run: bash extras/scripts/build-pio-dirs.sh + - name: Build on PlatformIO + run: bash extras/scripts/build-platformio.sh esp32_V6_0_1 diff --git a/.github/workflows/build_examples_esp32_V6_1_0.yml b/.github/workflows/build_examples_esp32_V6_1_0.yml new file mode 100644 index 00000000..8472315d --- /dev/null +++ b/.github/workflows/build_examples_esp32_V6_1_0.yml @@ -0,0 +1,21 @@ + +name: Build examples for esp32 @ V6_1_0 + +on: + push: + branches: [ master ] + pull_request: + branches: [ master ] + +jobs: + build: + + runs-on: ubuntu-latest + + steps: + - name: Checkout + uses: actions/checkout@v4 + - name: Make directories + run: bash extras/scripts/build-pio-dirs.sh + - name: Build on PlatformIO + run: bash extras/scripts/build-platformio.sh esp32_V6_1_0 diff --git a/.github/workflows/build_examples_esp32_V6_2_0.yml b/.github/workflows/build_examples_esp32_V6_2_0.yml new file mode 100644 index 00000000..ad19942a --- /dev/null +++ b/.github/workflows/build_examples_esp32_V6_2_0.yml @@ -0,0 +1,21 @@ + +name: Build examples for esp32 @ V6_2_0 + +on: + push: + branches: [ master ] + pull_request: + branches: [ master ] + +jobs: + build: + + runs-on: ubuntu-latest + + steps: + - name: Checkout + uses: actions/checkout@v4 + - name: Make directories + run: bash extras/scripts/build-pio-dirs.sh + - name: Build on PlatformIO + run: bash extras/scripts/build-platformio.sh esp32_V6_2_0 diff --git a/.github/workflows/build_examples_esp32_V6_3_2.yml b/.github/workflows/build_examples_esp32_V6_3_2.yml new file mode 100644 index 00000000..37eaeba6 --- /dev/null +++ b/.github/workflows/build_examples_esp32_V6_3_2.yml @@ -0,0 +1,21 @@ + +name: Build examples for esp32 @ V6_3_2 + +on: + push: + branches: [ master ] + pull_request: + branches: [ master ] + +jobs: + build: + + runs-on: ubuntu-latest + + steps: + - name: Checkout + uses: actions/checkout@v4 + - name: Make directories + run: bash extras/scripts/build-pio-dirs.sh + - name: Build on PlatformIO + run: bash extras/scripts/build-platformio.sh esp32_V6_3_2 diff --git a/.github/workflows/build_examples_esp32_V6_4_0.yml b/.github/workflows/build_examples_esp32_V6_4_0.yml new file mode 100644 index 00000000..729ef1e8 --- /dev/null +++ b/.github/workflows/build_examples_esp32_V6_4_0.yml @@ -0,0 +1,21 @@ + +name: Build examples for esp32 @ V6_4_0 + +on: + push: + branches: [ master ] + pull_request: + branches: [ master ] + +jobs: + build: + + runs-on: ubuntu-latest + + steps: + - name: Checkout + uses: actions/checkout@v4 + - name: Make directories + run: bash extras/scripts/build-pio-dirs.sh + - name: Build on PlatformIO + run: bash extras/scripts/build-platformio.sh esp32_V6_4_0 diff --git a/.github/workflows/build_examples_esp32_V6_5_0.yml b/.github/workflows/build_examples_esp32_V6_5_0.yml new file mode 100644 index 00000000..05c86d0d --- /dev/null +++ b/.github/workflows/build_examples_esp32_V6_5_0.yml @@ -0,0 +1,21 @@ + +name: Build examples for esp32 @ V6_5_0 + +on: + push: + branches: [ master ] + pull_request: + branches: [ master ] + +jobs: + build: + + runs-on: ubuntu-latest + + steps: + - name: Checkout + uses: actions/checkout@v4 + - name: Make directories + run: bash extras/scripts/build-pio-dirs.sh + - name: Build on PlatformIO + run: bash extras/scripts/build-platformio.sh esp32_V6_5_0 diff --git a/.github/workflows/build_examples_esp32_V6_6_0.yml b/.github/workflows/build_examples_esp32_V6_6_0.yml new file mode 100644 index 00000000..8c066c59 --- /dev/null +++ b/.github/workflows/build_examples_esp32_V6_6_0.yml @@ -0,0 +1,21 @@ + +name: Build examples for esp32 @ V6_6_0 + +on: + push: + branches: [ master ] + pull_request: + branches: [ master ] + +jobs: + build: + + runs-on: ubuntu-latest + + steps: + - name: Checkout + uses: actions/checkout@v4 + - name: Make directories + run: bash extras/scripts/build-pio-dirs.sh + - name: Build on PlatformIO + run: bash extras/scripts/build-platformio.sh esp32_V6_6_0 diff --git a/.github/workflows/build_examples_esp32arduinolatest.yml b/.github/workflows/build_examples_esp32arduinolatest.yml deleted file mode 100644 index e3c04a3f..00000000 --- a/.github/workflows/build_examples_esp32arduinolatest.yml +++ /dev/null @@ -1,21 +0,0 @@ -name: Build examples for esp32arduino @ latest - -on: - push: - branches: [ master ] - pull_request: - branches: [ master ] - -jobs: - build: - - runs-on: ubuntu-latest - - steps: - - name: Checkout - uses: actions/checkout@v3 - - name: Make directories - run: bash extras/scripts/build-pio-dirs.sh - - name: Build on PlatformIO - run: bash extras/scripts/build-platformio.sh esp32arduinolatest - diff --git a/.github/workflows/build_examples_esp32c3_V6_5_0.yml b/.github/workflows/build_examples_esp32c3_V6_5_0.yml new file mode 100644 index 00000000..e1e87e8e --- /dev/null +++ b/.github/workflows/build_examples_esp32c3_V6_5_0.yml @@ -0,0 +1,21 @@ + +name: Build examples for esp32c3 @ V6_5_0 + +on: + push: + branches: [ master ] + pull_request: + branches: [ master ] + +jobs: + build: + + runs-on: ubuntu-latest + + steps: + - name: Checkout + uses: actions/checkout@v4 + - name: Make directories + run: bash extras/scripts/build-pio-dirs.sh + - name: Build on PlatformIO + run: bash extras/scripts/build-platformio.sh esp32c3_V6_5_0 diff --git a/.github/workflows/build_examples_esp32s2_V6_5_0.yml b/.github/workflows/build_examples_esp32s2_V6_5_0.yml new file mode 100644 index 00000000..009bf496 --- /dev/null +++ b/.github/workflows/build_examples_esp32s2_V6_5_0.yml @@ -0,0 +1,21 @@ + +name: Build examples for esp32s2 @ V6_5_0 + +on: + push: + branches: [ master ] + pull_request: + branches: [ master ] + +jobs: + build: + + runs-on: ubuntu-latest + + steps: + - name: Checkout + uses: actions/checkout@v4 + - name: Make directories + run: bash extras/scripts/build-pio-dirs.sh + - name: Build on PlatformIO + run: bash extras/scripts/build-platformio.sh esp32s2_V6_5_0 diff --git a/.github/workflows/build_examples_esp32s3_V6_5_0.yml b/.github/workflows/build_examples_esp32s3_V6_5_0.yml new file mode 100644 index 00000000..266caad6 --- /dev/null +++ b/.github/workflows/build_examples_esp32s3_V6_5_0.yml @@ -0,0 +1,21 @@ + +name: Build examples for esp32s3 @ V6_5_0 + +on: + push: + branches: [ master ] + pull_request: + branches: [ master ] + +jobs: + build: + + runs-on: ubuntu-latest + + steps: + - name: Checkout + uses: actions/checkout@v4 + - name: Make directories + run: bash extras/scripts/build-pio-dirs.sh + - name: Build on PlatformIO + run: bash extras/scripts/build-platformio.sh esp32s3_V6_5_0 diff --git a/.github/workflows/build_examples_nanoatmega168.yml b/.github/workflows/build_examples_nanoatmega168.yml index 95bc4469..60b1d51d 100644 --- a/.github/workflows/build_examples_nanoatmega168.yml +++ b/.github/workflows/build_examples_nanoatmega168.yml @@ -13,7 +13,7 @@ jobs: steps: - name: Checkout - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Make directories run: bash extras/scripts/build-pio-dirs.sh - name: Build on PlatformIO diff --git a/.github/workflows/build_examples_nanoatmega328.yml b/.github/workflows/build_examples_nanoatmega328.yml index 35340d14..d82e1cd4 100644 --- a/.github/workflows/build_examples_nanoatmega328.yml +++ b/.github/workflows/build_examples_nanoatmega328.yml @@ -13,7 +13,7 @@ jobs: steps: - name: Checkout - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Make directories run: bash extras/scripts/build-pio-dirs.sh - name: Build on PlatformIO diff --git a/.github/workflows/test.yml b/.github/workflows/test.yml index 2b93a42e..61dd9302 100644 --- a/.github/workflows/test.yml +++ b/.github/workflows/test.yml @@ -12,6 +12,6 @@ jobs: runs-on: ubuntu-latest steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 - name: make run: make -C extras/tests/pc_based diff --git a/.github/workflows/test_avr.yml b/.github/workflows/test_avr.yml index 9b0b404e..e28f1fb7 100644 --- a/.github/workflows/test_avr.yml +++ b/.github/workflows/test_avr.yml @@ -12,7 +12,7 @@ jobs: runs-on: ubuntu-20.04 steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 - name: get platformio run: curl -fsSL https://raw.githubusercontent.com/platformio/platformio-core-installer/master/get-platformio.py -o get-platformio.py - name: install platformio diff --git a/.gitignore b/.gitignore index 65a06c31..782b9324 100644 --- a/.gitignore +++ b/.gitignore @@ -20,7 +20,7 @@ extras/tests/pc_based/RampGenerator.cpp extras/tests/pc_based/RampGenerator.h extras/tests/pc_based/StepperISR*.cpp extras/tests/pc_based/StepperISR.h -extras/tests/pc_based/common.h +extras/tests/pc_based/fas_common.h extras/tests/pc_based/*.gnuplot extras/tests/pc_based/*_test extras/tests/pc_based/test.log @@ -32,3 +32,4 @@ extras/tests/simavr_based/test_sd*/Makefile extras/tests/simavr_based/test_seq*/Makefile extras/tests/esp32_hw_based/*.log library.properties +examples diff --git a/CHANGELOG.md b/CHANGELOG.md index 32b544da..28d83b41 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,12 +1,50 @@ TODO: -- Different behavior avr vs pc-based tests to be analyzed +- Different behavior avr vs pc-based testgis to be analyzed - #include-file structure needs to be cleaned up - setCurrentPosition() should adjust the maintained last position bits in queue. can be called a bug - rename PoorManFloat to e.g. Log2Representation - rename RampConstAcceleration to e.g. RampControl +- merge the two esp32 rmt drivers as soon as esp32c3 works -pre-0.30.5: +0.30.13: +- avr: rework Stepper-ISR routine. It should now be robust against interrupt blockage in regard to steps lost. If interrupt blockage is too long, then 4ms paus could occur between two steps. +- avr: Interrupt blockage of 30us tested and passed +- Add configurable forward planning time for filling the stepper queue (#253) +- avr: make `setAbsoluteSpeedLimit()` available + +0.30.12: +- esp32: fix deprecation warning for `rmt_memory_rw_rst()` +- esp32: add build test for platform espressif v6.6.0 with arduino core (#251) +- simavr-tests: automatically create links/makefiles +- avr: Fix issue #250 +- avr: In course of issue #250, interrupt blocks of 20us from application are tested. + +0.30.11: +- esp32s3: add support for rmt from patch #225 + +0.30.10: +- Unify code in stepperConnectToPin to fix bug mentioned in #221 + This ensures setting of per stepper speed limit is working for avr variants without side effect + of uncontrolled write to I/O-region +- rename `common.h` to `fas_common.h` as proposed in #220 + +0.30.9: +- Fix esp32s3 to support the fourth stepper (issue #212) + +0.30.8: +- Implement `setAbsoluteSpeedLimit(uint16_t max_speed_in_ticks)` as proposed by issue #210 + +0.30.7: +- Fix for issue #208: the sign of current speed may be incorrect close to direction change +- The functions `getCurrentSpeedInMilliHz()` and `getCurrentSpeedInUs()` have been extended to supply a bool parameter about being realtime. + +0.30.6: +- Support for ESP32C3 +- Fix for missing `_stepper_cnt` initialization (patch #204) + +0.30.5: - Fix target position for a move() interrupting the keep running mode +- Fix issue #199: add initialization of `_enablePinHighActive` and `_enablePinLowActive` 0.30.4: - Fix for issue #178: speed does not decelerate but jumps to lower value diff --git a/README.md b/README.md index 8995d86c..9035ef52 100644 --- a/README.md +++ b/README.md @@ -1,4 +1,4 @@ -# BE AWARE: ARDUINO LIBRARY MANAGER IS BROKEN AND 0.29.x do not show. +# BE AWARE: ARDUINO LIBRARY MANAGER IS BROKEN AND 0.29.x/0.30.x with x>0 do not show. No issue with platformio. Check the [related issue](https://github.com/arduino/library-registry/issues/2829) for the arduino library manager @@ -14,17 +14,47 @@ No issue with platformio. Check the [related issue](https://github.com/arduino/l ![Run tests](https://github.com/gin66/FastAccelStepper/workflows/Run%20tests/badge.svg?no_cache_0.28.1) ![Simvar tests](https://github.com/gin66/FastAccelStepper/workflows/Run%20tests%20with%20simavr/badge.svg?no_cache_0.28.1) -[![Build examples for esp32](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32.yml/badge.svg)](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32.yml) -[![Build examples for esp32s2](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32s2.yml/badge.svg)](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32s2.yml) -[![Build examples for esp32arduino @ 3.4.0](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32arduinoV340.yml/badge.svg)](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32arduinoV340.yml) -[![Build examples for esp32arduino @ latest](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32arduinolatest.yml/badge.svg)](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32arduinolatest.yml) +## Build for ESP32-platform + +Build examples for different versions of espressif-arduino platform: + +### esp32 +[![`V6_6_0`](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32_V6_6_0.yml/badge.svg)](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32_V6_6_0.yml) +[![`V6_5_0`](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32_V6_5_0.yml/badge.svg)](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32_V6_5_0.yml) +[![`V6_4_0`](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32_V6_4_0.yml/badge.svg)](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32_V6_4_0.yml) +[![`V6_3_2`](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32_V6_3_2.yml/badge.svg)](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32_V6_3_2.yml) +[![`V6_2_0`](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32_V6_2_0.yml/badge.svg)](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32_V6_2_0.yml) +[![`V6_1_0`](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32_V6_1_0.yml/badge.svg)](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32_V6_1_0.yml) +[![`V6_0_1`](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32_V6_0_1.yml/badge.svg)](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32_V6_0_1.yml) +[![`V5_3_0`](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32_V5_3_0.yml/badge.svg)](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32_V5_3_0.yml) +[![`V5_2_0`](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32_V5_2_0.yml/badge.svg)](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32_V5_2_0.yml) +[![`V5_1_1`](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32_V5_1_1.yml/badge.svg)](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32_V5_1_1.yml) +[![`V5_0_0`](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32_V5_0_0.yml/badge.svg)](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32_V5_0_0.yml) +[![`V4_4_0`](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32_V4_4_0.yml/badge.svg)](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32_V4_4_0.yml) +[![`V4_3_0`](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32_V4_3_0.yml/badge.svg)](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32_V4_3_0.yml) +[![`V4_2_0`](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32_V4_2_0.yml/badge.svg)](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32_V4_2_0.yml) +[![`V4_1_0`](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32_V4_1_0.yml/badge.svg)](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32_V4_1_0.yml) +[![`V3_5_0`](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32_V3_5_0.yml/badge.svg)](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32_V3_5_0.yml) + +### esp32s2 +[![`V6_5_0`](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32s2_V6_5_0.yml/badge.svg)](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32s2_V6_5_0.yml) + +### esp32s3 +[![`V6_5_0`](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32s3_V6_5_0.yml/badge.svg)](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32s3_V6_5_0.yml) + +### esp32c3 +[![`V6_5_0`](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32c3_V6_5_0.yml/badge.svg)](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_esp32c3_V6_5_0.yml) + +## Build for avr-platform [![Build examples for Atmega2560](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_atmega2560.yml/badge.svg)](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_atmega2560.yml) [![Build examples for Atmel SAM](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_atmelsam.yml/badge.svg)](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_atmelsam.yml) [![Build examples for Atmega168/328](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_nanoatmega328.yml/badge.svg)](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_nanoatmega328.yml) [![Build examples for Atmega32U4](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_atmega32u4.yml/badge.svg)](https://github.com/gin66/FastAccelStepper/actions/workflows/build_examples_nanoatmega32u4.yml) +## Overview + This is a high speed alternative for the [AccelStepper library](http://www.airspayce.com/mikem/arduino/AccelStepper/). -Supported are avr (ATmega 168/328/P, ATmega2560, ATmega32u4), esp32, esp32s2, esp32s3 and atmelsam due. +Supported are avr (ATmega 168/328/P, ATmega2560, ATmega32u4), esp32, esp32s2, esp32s3, esp32c3 and atmelsam due. The stepper motors should be connected via a driver IC (like A4988) with a 1, 2 or 3-wire connection: * Step Signal @@ -66,6 +96,11 @@ FastAccelStepper offers the following features: * Provide API to each steppers' command queue. Those commands are tied to timer ticks aka the CPU frequency! * Command queue can be filled with commands and then started. This allows near synchronous start of several steppers for multi axis applications. +## Star History + +[![Star History Chart](https://api.star-history.com/svg?repos=gin66/FastAccelStepper&type=Date)](https://star-history.com/#gin66/FastAccelStepper&Date) + + General behaviour: * The desired end position to move to is set by calls to moveTo() and move() * The desired end position is in case of moveTo() given as absolute position @@ -142,7 +177,13 @@ Comments to pin sharing: ### ESP32S3 * allows up to 200000 generated steps per second ? -* supports up to four stepper motors using Step/Direction/Enable Control (Direction and Enable is optional) +* supports up to eight stepper motors using Step/Direction/Enable Control (Direction and Enable is optional) +* Steppers' command queue depth: 32 + +### ESP32C3 + +* allows up to 200000 generated steps per second ? +* supports up to two stepper motors using Step/Direction/Enable Control (Direction and Enable is optional) * Steppers' command queue depth: 32 ### Atmel SAM Due @@ -273,7 +314,7 @@ What are the differences between mcpwm/pcnt and rmt ? |:---------------------------|:----------------------------------------|:------------------------------------------------------------------------------| |Interrupt rate/stepper | one interrupt per command | min: one interrupt per command, max: one interrupt per 31 steps at high speed | |Required interrupt response | at high speed: time between two steps | at high speed: time between 31 steps | -|Module usage    | 1 or 2 mcpcms, up to 6 channels of pcnt | rmt | +|Module usage | 1 or 2 mcpcms, up to 6 channels of pcnt | rmt | |esp32 notes | availabe pcnt modules can be connected | no pcnt module used, so can be attached to rmt output as realtime position | If the interrupt load is not an issue, then rmt is the better choice. With rmt the below (multi-axis application) mentioned loss of synchonicity at high speeds can be avoided. The rmt driver is - besides some rmt modules perks - less complex and way more straightforward. @@ -288,11 +329,15 @@ This stepper driver uses rmt module. ### ESP32S3 -This stepper driver uses mcpwm/pcnt modules. Can drive up to 4 motors. Tested with 2 motors. +This stepper driver uses mcpwm/pcnt + rmt modules. Can drive up to 8 motors. Tested with 6 motors (not by me). -### ESP32C3/ESP32-MINI-1 +The ESP32S3's rmt module is similar to esp32c3 with 4 instead of 2 channels and with different register names. -Compatibility with ESP32-C3: Not supported currently. The rmt module has more changes compared to esp32/esp32s2 +### ESP32C3 + +This stepper driver uses rmt module and can drive up to 2 motors. Not thoroughly tested, so only experimental support. + +### ESP32-MINI-1 Compatibility with ESP32-MINI-1: At least mcpwm and pulse counter modules are listed in the datasheet. So there are chances, that this lib works. @@ -431,6 +476,7 @@ This feature of StepperDemo allows to compare non-smooth running stepper in an a * In one setup, operating A4988 without microsteps has led to erratic behaviour at some specific low speed (erratic means step forward/backward, while DIR is kept low). No issue with 16 microstep. These two youtube videos show similar behavior: [hard disc stepper](https://youtu.be/DsYgw3GFHZo) and [axes movement](https://youtu.be/Nw18B81Ylhk) * The pulse counters in esp32 have several comparators to trigger interrupts. What the documentation does not mention: All those reference values are only forwarded to the actual comparator on pulse counter reset. Thus the pulse counters cannot be used as lower 16bit of the position, unfortunately. * The [issue #60](https://github.com/gin66/FastAccelStepper/issues/60) was raised due to wrong position on negative moves with esp32. Apparently the issue was with proper ground and/or power lines to the stepper driver. If similar issue is encountered, please check on this issue +* ESP32C3: USBSerial works only under Arduino IDE. platformio support for USBSerial is missing ## 3rd party videos in action @@ -453,4 +499,6 @@ As mentioned by kthod861 in [Issue #110](https://github.com/gin66/FastAccelStepp - Thanks clazarowitz for the amazing atmel sam due port (https://github.com/gin66/FastAccelStepper/pull/82) - Thanks HeldeReis for the awesome ESP32-S3 port (https://github.com/gin66/FastAccelStepper/pull/162) - Thanks DaAwesomeP for the extension to ATmega 168/168P/328 (https://github.com/gin66/FastAccelStepper/pull/179) - +- Thanks turley for the patch for missing `_stepper_cnt` initialization (https://github.com/gin66/FastAccelStepper/pull/204) +- Thanks GarmischWg for adding rmt-support to ESP32-S3 (https://github.com/gin66/FastAccelStepper/pull/225) +- THanks SHWotever for avr patch to fix missing direction pin toggle (https://github.com/gin66/FastAccelStepper/pull/252) diff --git a/examples/Issue208/Issue208.ino b/examples/Issue208/Issue208.ino new file mode 100644 index 00000000..d4ec04c0 --- /dev/null +++ b/examples/Issue208/Issue208.ino @@ -0,0 +1,134 @@ +#include "FastAccelStepper.h" +#include +#ifdef SIMULATOR +#include +#endif + +#if defined(ARDUINO_ARCH_AVR) +#include "AVRStepperPins.h" +#define dirPinStepperAVR 5 +#define stepPinStepperAVR stepPinStepperA +#define enablePinStepperAVR 6 +#elif defined(ARDUINO_ARCH_ESP32) +#define dirPinStepperESP 18 +#define stepPinStepperESP 17 +#define enablePinStepperESP 26 +#endif + +FastAccelStepperEngine engine = FastAccelStepperEngine(); +FastAccelStepper *stepper; + +bool test() { + bool verbose = false; + int32_t errCnt = 0; + Serial.println("Start test: speed up"); + int32_t last_v_mHz = 0; + stepper->setAcceleration(10000); + stepper->setSpeedInHz(36800); + stepper->runForward(); + + while (stepper->rampState() != (RAMP_STATE_COAST | RAMP_DIRECTION_COUNT_UP)) { + int32_t v_mHz = stepper->getCurrentSpeedInMilliHz(false); + if (v_mHz == last_v_mHz) { + continue; + } + if (verbose) Serial.println(v_mHz); + if (v_mHz < last_v_mHz) { + Serial.print("FAIL: last="); + Serial.print(last_v_mHz); + Serial.print(" new="); + Serial.println(v_mHz); + errCnt++; + // return false; + } + last_v_mHz = v_mHz; + } + // There can be still speed increases in the queue, even so the ramp generator + // is already coasting + delay(20); + last_v_mHz = stepper->getCurrentSpeedInMilliHz(false); + + Serial.println("Reverse"); + + stepper->runBackward(); + + while (stepper->rampState() != + (RAMP_STATE_COAST | RAMP_DIRECTION_COUNT_DOWN)) { + int32_t v_mHz = stepper->getCurrentSpeedInMilliHz(false); + if (v_mHz == last_v_mHz) { + continue; + } + if (verbose) Serial.println(v_mHz); + if (v_mHz > last_v_mHz) { + Serial.print("FAIL: last="); + Serial.print(last_v_mHz); + Serial.print(" new="); + Serial.println(v_mHz); + errCnt++; + // return false; + } + last_v_mHz = v_mHz; + } + if (errCnt > 0) { + Serial.print("Errors="); + Serial.println(errCnt); + } + return errCnt == 0; +} + +void setup() { + Serial.begin(115200); + Serial.println("Init"); + engine.init(); + + // pins are set to outputs here automatically +#if defined(ARDUINO_ARCH_AVR) + Serial.println("AVR"); + Serial.println(stepPinStepperAVR); + stepper = engine.stepperConnectToPin(stepPinStepperAVR); + stepper->setDirectionPin(dirPinStepperAVR); +// stepper->setEnablePin(enablePinStepperAVR, true); +#elif defined(ARDUINO_ARCH_ESP32) + stepper = engine.stepperConnectToPin(stepPinStepperESP); + stepper->setDirectionPin(dirPinStepperESP); + stepper->setEnablePin(enablePinStepperESP, true); +#endif + + stepper->setAutoEnable(true); + Serial.println(stepper != NULL ? "OK" : "ERROR"); + Serial.println("Done"); + + bool pass = test(); + stepper->stopMove(); + +#ifndef SIMULATOR + if (pass) { + Serial.print("PASS"); + } else { + Serial.print("FAIL"); + } +#endif + +#ifdef SIMULATOR + // if result is Ok. Toggle port twice, otherwise once +#define PIN stepPinStepperB +#define DIRPIN 7 + pinMode(DIRPIN, OUTPUT); + digitalWrite(DIRPIN, HIGH); + pinMode(PIN, OUTPUT); + digitalWrite(PIN, HIGH); + digitalWrite(PIN, LOW); + if (pass) { + Serial.println("PASS"); + digitalWrite(PIN, HIGH); + digitalWrite(PIN, LOW); + } else { + Serial.println("FAIL"); + } + delay(1000); + noInterrupts(); + sleep_cpu(); +#endif +} + +void loop() {} diff --git a/examples/Issue250/Issue250.ino b/examples/Issue250/Issue250.ino new file mode 100644 index 00000000..ef67c37f --- /dev/null +++ b/examples/Issue250/Issue250.ino @@ -0,0 +1,100 @@ +#include "FastAccelStepper.h" + +#ifdef SIMULATOR +#include +#include +#endif + +// As in StepperDemo for Motor 1 on AVR +#define dirPinStepper 5 +#define enablePinStepper 6 +#define stepPinStepper 9 // OC1A in case of AVR + +// As in StepperDemo for Motor 1 on ESP32 +//#define dirPinStepper 18 +//#define enablePinStepper 26 +//#define stepPinStepper 19 + +FastAccelStepperEngine engine = FastAccelStepperEngine(); +FastAccelStepper *stepper = NULL; + +void setup() { + Serial.begin(115200); + engine.init(); + stepper = engine.stepperConnectToPin(stepPinStepper); + if (stepper) { + stepper->setDirectionPin(dirPinStepper); + stepper->setEnablePin(enablePinStepper); + stepper->setAutoEnable(true); + + // If auto enable/disable need delays, just add (one or both): + stepper->setDelayToEnable(50); + stepper->setDelayToDisable(50); + + stepper->setSpeedInHz(40000); + stepper->setAcceleration(100000); + } +} + +uint16_t loopcnt = 0; + +// fails with blocking 30us +#ifndef BLOCK_INTERRUPT_US +#define BLOCK_INTERRUPT_US 20 +#endif +#ifndef TOGGLE_DIRECTION +#define TOGGLE_DIRECTION true +#endif +#ifndef USE_MOVETO +#define USE_MOVETO true +#endif +#ifndef LOOPS +#define LOOPS 200 +#endif + +uint32_t previous_runtime = 0; + +void loop() { + loopcnt++; + Serial.print("Loop="); + Serial.println(loopcnt); + uint32_t runtime = (rand() % 50) + 50; + if (((loopcnt & 1) == 1) || !TOGGLE_DIRECTION) { + if (USE_MOVETO) { + stepper->moveTo(10000); + } else { + stepper->runForward(); + } + } else { + if (USE_MOVETO) { + stepper->moveTo(-10000); + } else { + stepper->runBackward(); + } + } + uint32_t start_ms = millis(); + while (millis() < 2 * previous_runtime + runtime + start_ms) { + noInterrupts(); +#ifdef SIMULATOR + _delay_us(BLOCK_INTERRUPT_US); +#endif + interrupts(); + } + previous_runtime = runtime; + + if (loopcnt == LOOPS) { + stepper->stopMove(); + while (stepper->isRunning()) { + } +#ifdef SIMULATOR + Serial.print("Reached Position="); + Serial.println(stepper->getCurrentPosition()); + stepper->moveTo(0, true); + Serial.print("Position="); + Serial.println(stepper->getCurrentPosition()); + delay(100); + noInterrupts(); + sleep_cpu(); +#endif + } +} diff --git a/examples/StepperDemo/StepperDemo.ino b/examples/StepperDemo/StepperDemo.ino index d32759d4..c2f9375d 100644 --- a/examples/StepperDemo/StepperDemo.ino +++ b/examples/StepperDemo/StepperDemo.ino @@ -124,9 +124,13 @@ const struct stepper_config_s stepper_config[MAX_STEPPER] = { #elif defined(ARDUINO_ARCH_ESP32) // Example hardware configuration for esp32 board. // Please adapt to your configuration +#ifdef CONFIG_IDF_TARGET_ESP32C3 +const uint8_t led_pin = 8; +#else const uint8_t led_pin = PIN_UNDEFINED; +#endif const struct stepper_config_s stepper_config[MAX_STEPPER] = { - // clang-format off +// clang-format off // Test-HW // Position 01 linked to atmega nano // 2: Enable Left Pin 13 GPIO13 , DIR Right Pin 7 GPIO18, Step Right Pin 13 GPIO15 @@ -137,7 +141,31 @@ const struct stepper_config_s stepper_config[MAX_STEPPER] = { // 7: Enable Left Pin 8 GPIO25 A8, DIR Right Pin 2 GPIO22, Step Right Pin 8 GPIO5 // ALL Enable: Right Pin 1 GPIO23 // Left Pin 15: +5V - // clang-format on +// clang-format on +#ifdef CONFIG_IDF_TARGET_ESP32C3 + { + step : 6, + enable_low_active : PIN_UNDEFINED, + enable_high_active : PIN_UNDEFINED, + direction : PIN_UNDEFINED, + dir_change_delay : 0, + direction_high_count_up : true, + auto_enable : true, + on_delay_us : 50, + off_delay_ms : 1000 + }, + { + step : 7, + enable_low_active : PIN_UNDEFINED, + enable_high_active : PIN_UNDEFINED, + direction : PIN_UNDEFINED, + dir_change_delay : 0, + direction_high_count_up : true, + auto_enable : true, + on_delay_us : 500, + off_delay_ms : 1000 + } +#else { // position 01.234567 => 2 step : 17, @@ -163,6 +191,7 @@ const struct stepper_config_s stepper_config[MAX_STEPPER] = { on_delay_us : 500, off_delay_ms : 1000 } +#endif #if MAX_STEPPER > 2 , { @@ -794,7 +823,7 @@ void output_msg(uint8_t x) { if (y <= MSG_USAGE_CONFIG) { output_msg(y); } else { - Serial.print(ch); + SerialInterface.print(ch); } } } @@ -822,7 +851,7 @@ void setDirectionPin(uint8_t direction, bool polarity) { delay10us(); if (digitalRead(direction) != polarity) { output_msg(MSG_CANNOT_SET_DIRECTION_PIN); - Serial.println(polarity ? "HIGH" : "LOW"); + SerialInterface.println(polarity ? "HIGH" : "LOW"); } } } @@ -853,9 +882,11 @@ void test_direct_drive(const struct stepper_config_s *stepper) { output_msg(MSG_ENABLE_HIGH_PIN_IS_NOT_HIGH); } } - setDirectionPin(direction, direction_high_count_up); - do3200Steps(step); - setDirectionPin(direction, !direction_high_count_up); + if (direction != PIN_UNDEFINED) { + setDirectionPin(direction, direction_high_count_up); + do3200Steps(step); + setDirectionPin(direction, !direction_high_count_up); + } do3200Steps(step); if (enableLow != PIN_UNDEFINED) { digitalWrite(enableLow, HIGH); @@ -876,12 +907,19 @@ void test_direct_drive(const struct stepper_config_s *stepper) { #endif void setup() { - Serial.begin(115200); + SerialInterface.begin(115200); +#ifdef CONFIG_IDF_TARGET_ESP32C3 + while (!Serial) { + ; // wait for USB serial port to connect. + } +#endif + output_msg(MSG_STEPPER_VERSION); - Serial.print(" F_CPU="); - Serial.println(F_CPU); - Serial.print(" TICKS_PER_S="); - Serial.println(TICKS_PER_S); + SerialInterface.print(" F_CPU="); + SerialInterface.println(F_CPU); + SerialInterface.print(" TICKS_PER_S="); + SerialInterface.println(TICKS_PER_S); + SerialInterface.println(MAX_STEPPER); // If you are not sure, that the stepper hardware is working, // then try first direct port manipulation and uncomment the next line. @@ -939,86 +977,86 @@ bool simulate_digitalRead_error = false; bool simulate_blocked_ISR = false; void info(FastAccelStepper *s, bool long_info) { - Serial.print('@'); + SerialInterface.print('@'); #if defined(SUPPORT_ESP32_PULSE_COUNTER) if (s->pulseCounterAttached()) { int16_t pcnt_pos_1 = s->readPulseCounter(); int32_t pos = s->getCurrentPosition(); int16_t pcnt_pos_2 = s->readPulseCounter(); - Serial.print(pos); - Serial.print(" ["); - Serial.print(pcnt_pos_1); - Serial.print(']'); + SerialInterface.print(pos); + SerialInterface.print(" ["); + SerialInterface.print(pcnt_pos_1); + SerialInterface.print(']'); if (pcnt_pos_1 != pcnt_pos_2) { - Serial.print(" ["); - Serial.print(pcnt_pos_2); - Serial.print(']'); + SerialInterface.print(" ["); + SerialInterface.print(pcnt_pos_2); + SerialInterface.print(']'); } } else { int32_t pos = s->getCurrentPosition(); - Serial.print(pos); + SerialInterface.print(pos); } #else int32_t pos = s->getCurrentPosition(); - Serial.print(pos); + SerialInterface.print(pos); #endif if (s->isRunning()) { if (s->isRunningContinuously()) { - Serial.print(" nonstop"); + SerialInterface.print(" nonstop"); } else { - Serial.print(" => "); - Serial.print(s->targetPos()); + SerialInterface.print(" => "); + SerialInterface.print(s->targetPos()); } - Serial.print(" QueueEnd="); - Serial.print(s->getPositionAfterCommandsCompleted()); + SerialInterface.print(" QueueEnd="); + SerialInterface.print(s->getPositionAfterCommandsCompleted()); if (speed_in_milli_hz) { - Serial.print(" v="); - Serial.print(s->getCurrentSpeedInMilliHz()); - Serial.print("mSteps/s"); + SerialInterface.print(" v="); + SerialInterface.print(s->getCurrentSpeedInMilliHz()); + SerialInterface.print("mSteps/s"); } else { - Serial.print('/'); - Serial.print(s->getPeriodInUsAfterCommandsCompleted()); - Serial.print("us/"); - Serial.print(s->getPeriodInTicksAfterCommandsCompleted()); - Serial.print("ticks"); + SerialInterface.print('/'); + SerialInterface.print(s->getPeriodInUsAfterCommandsCompleted()); + SerialInterface.print("us/"); + SerialInterface.print(s->getPeriodInTicksAfterCommandsCompleted()); + SerialInterface.print("ticks"); } if (s->isRampGeneratorActive()) { switch (s->rampState() & RAMP_STATE_MASK) { case RAMP_STATE_IDLE: - Serial.print(" IDLE "); + SerialInterface.print(" IDLE "); break; case RAMP_STATE_ACCELERATE: - Serial.print(" ACC "); + SerialInterface.print(" ACC "); break; case RAMP_STATE_DECELERATE: - Serial.print(" RED "); // Reduce + SerialInterface.print(" RED "); // Reduce break; case RAMP_STATE_COAST: - Serial.print(" COAST"); + SerialInterface.print(" COAST"); break; case RAMP_STATE_REVERSE: - Serial.print(" REV "); + SerialInterface.print(" REV "); break; default: - Serial.print(s->rampState()); + SerialInterface.print(s->rampState()); } } else { - Serial.print(" MANU"); + SerialInterface.print(" MANU"); } } else { if (long_info) { output_msg(MSG_ACCELERATION_STATUS); - Serial.print(s->getAcceleration()); + SerialInterface.print(s->getAcceleration()); if (speed_in_milli_hz) { output_msg(MSG_SPEED_STATUS_FREQ); - Serial.print(s->getSpeedInMilliHz()); + SerialInterface.print(s->getSpeedInMilliHz()); } else { output_msg(MSG_SPEED_STATUS_TIME); - Serial.print(s->getSpeedInUs()); + SerialInterface.print(s->getSpeedInUs()); } } } - Serial.print(' '); + SerialInterface.print(' '); } void stepper_info() { @@ -1054,18 +1092,18 @@ void output_info(bool only_running) { if (stepper[i]) { if (!only_running) { if (i == selected) { - Serial.print(">> "); + SerialInterface.print(">> "); } else { - Serial.print(" "); + SerialInterface.print(" "); } } if (!only_running || stepper[i]->isRunning()) { - Serial.print('M'); - Serial.print(i + 1); - Serial.print(": "); + SerialInterface.print('M'); + SerialInterface.print(i + 1); + SerialInterface.print(": "); info(stepper[i], !only_running); if (!only_running) { - Serial.println(); + SerialInterface.println(); } else { need_ln = true; } @@ -1073,7 +1111,7 @@ void output_info(bool only_running) { } } if (need_ln) { - Serial.println(); + SerialInterface.println(); } } @@ -1112,7 +1150,7 @@ bool process_cmd(char *cmd) { if ((val_n[0] > 0) && (val_n[0] <= MAX_STEPPER)) { output_msg(MSG_SELECT_STEPPER); selected = val_n[0] - 1; - Serial.println(selected + 1); + SerialInterface.println(selected + 1); return true; } } @@ -1120,13 +1158,13 @@ bool process_cmd(char *cmd) { case MODE(normal, 'r'): #if defined(ARDUINO_ARCH_ESP32) if (strcmp(cmd, "eset") == 0) { - Serial.println("ESP reset"); + SerialInterface.println("ESP reset"); esp_task_wdt_init(1, true); esp_task_wdt_add(NULL); while (true) ; } - Serial.println("ESP restart"); + SerialInterface.println("ESP restart"); ESP.restart(); #endif #if defined(ARDUINO_ARCH_AVR) @@ -1188,7 +1226,7 @@ bool process_cmd(char *cmd) { val_n[0] = strtol(cmd, &endptr, 10); if (*endptr == 0) { output_msg(MSG_SET_ACCELERATION_TO); - Serial.println(val_n[0]); + SerialInterface.println(val_n[0]); res = stepper_selected->setAcceleration(val_n[0]); if (res < 0) { output_msg(MSG_ERROR_INVALID_VALUE); @@ -1200,7 +1238,7 @@ bool process_cmd(char *cmd) { val_n[0] = strtol(cmd, &endptr, 10); if (*endptr == 0) { output_msg(MSG_LINEAR_ACCELERATION); - Serial.println(val_n[0]); + SerialInterface.println(val_n[0]); stepper_selected->setLinearAcceleration(val_n[0]); return true; } @@ -1209,7 +1247,7 @@ bool process_cmd(char *cmd) { val_n[0] = strtol(cmd, &endptr, 10); if (*endptr == 0) { output_msg(MSG_JUMP_START); - Serial.println(val_n[0]); + SerialInterface.println(val_n[0]); stepper_selected->setJumpStart(val_n[0]); return true; } @@ -1219,7 +1257,7 @@ bool process_cmd(char *cmd) { if (*endptr == 0) { speed_in_milli_hz = false; output_msg(MSG_SET_SPEED_TO_US); - Serial.println(val_n[0]); + SerialInterface.println(val_n[0]); res = stepper_selected->setSpeedInUs(val_n[0]); if (res < 0) { output_msg(MSG_ERROR_INVALID_VALUE); @@ -1232,7 +1270,7 @@ bool process_cmd(char *cmd) { if (*endptr == 0) { speed_in_milli_hz = true; output_msg(MSG_SET_SPEED_TO_HZ); - Serial.println(val_n[0]); + SerialInterface.println(val_n[0]); res = stepper_selected->setSpeedInHz(val_n[0]); if (res < 0) { output_msg(MSG_ERROR_INVALID_VALUE); @@ -1245,7 +1283,7 @@ bool process_cmd(char *cmd) { if (*endptr == 0) { speed_in_milli_hz = true; output_msg(MSG_SET_SPEED_TO_MILLI_HZ); - Serial.println(val_n[0]); + SerialInterface.println(val_n[0]); res = stepper_selected->setSpeedInMilliHz(val_n[0]); if (res < 0) { output_msg(MSG_ERROR_INVALID_VALUE); @@ -1257,7 +1295,7 @@ bool process_cmd(char *cmd) { val_n[0] = strtol(cmd, &endptr, 10); if (*endptr == 0) { output_msg(MSG_SET_ACCELERATION_TO); - Serial.println(val_n[0]); + SerialInterface.println(val_n[0]); res = stepper_selected->moveByAcceleration(val_n[0]); output_msg(MSG_MOVE_OK + res); return true; @@ -1267,7 +1305,7 @@ bool process_cmd(char *cmd) { val_n[0] = strtol(cmd, &endptr, 10); if (*endptr == 0) { output_msg(MSG_MOVE_STEPS); - Serial.println(val_n[0]); + SerialInterface.println(val_n[0]); res = stepper_selected->move(val_n[0]); output_msg(MSG_MOVE_OK + res); return true; @@ -1277,7 +1315,7 @@ bool process_cmd(char *cmd) { val_n[0] = strtol(cmd, &endptr, 10); if (*endptr == 0) { output_msg(MSG_MOVE_TO_POSITION); - Serial.println(val_n[0]); + SerialInterface.println(val_n[0]); res = stepper_selected->moveTo(val_n[0]); output_msg(MSG_MOVE_OK + res); return true; @@ -1287,7 +1325,7 @@ bool process_cmd(char *cmd) { val_n[0] = strtol(cmd, &endptr, 10); if (*endptr == 0) { output_msg(MSG_SET_POSITION); - Serial.println(val_n[0]); + SerialInterface.println(val_n[0]); stepper_selected->setCurrentPosition(val_n[0]); return true; } @@ -1296,10 +1334,10 @@ bool process_cmd(char *cmd) { val_n[0] = strtol(cmd, &endptr, 10); if (*endptr == 0) { output_msg(MSG_SET_ENABLE_TIME); - Serial.println(val_n[0]); + SerialInterface.println(val_n[0]); res = stepper_selected->setDelayToEnable(val_n[0]); output_msg(MSG_RETURN_CODE); - Serial.println(res); + SerialInterface.println(res); return true; } break; @@ -1307,7 +1345,7 @@ bool process_cmd(char *cmd) { val_n[0] = strtol(cmd, &endptr, 10); if (*endptr == 0) { output_msg(MSG_SET_DISABLE_TIME); - Serial.println(val_n[0]); + SerialInterface.println(val_n[0]); stepper_selected->setDelayToDisable(val_n[0]); return true; } @@ -1315,7 +1353,7 @@ bool process_cmd(char *cmd) { case MODE(normal, 'w'): val_n[0] = strtol(cmd, &endptr, 10); if (*endptr == 0) { - Serial.print(val_n[0]); + SerialInterface.print(val_n[0]); output_msg(MSG_WAIT_MS); pause_ms = val_n[0]; pause_start = millis(); @@ -1333,26 +1371,26 @@ bool process_cmd(char *cmd) { case 1: output_msg(MSG_DIRECTION_PIN); output_msg(MSG_SET_TO_PIN); - Serial.println(val_n[0]); + SerialInterface.println(val_n[0]); stepper_selected->setDirectionPin(val_n[0]); return true; case 2: case 3: output_msg(MSG_DIRECTION_PIN); output_msg(MSG_SET_TO_PIN); - Serial.println(val_n[0]); + SerialInterface.println(val_n[0]); output_msg(MSG_DIRECTION_PIN); if (val_n[1] != 0) { output_msg(MSG_HIGH_COUNT_DOWN); } else { output_msg(MSG_HIGH_COUNT_UP); } - Serial.println(); + SerialInterface.println(); if (gv == 2) { stepper_selected->setDirectionPin(val_n[0], val_n[1]); } else { output_msg(MSG_DELAY); - Serial.println(val_n[2]); + SerialInterface.println(val_n[2]); stepper_selected->setDirectionPin(val_n[0], val_n[1], val_n[2]); } return true; @@ -1401,7 +1439,7 @@ bool process_cmd(char *cmd) { output_msg(MSG_RUN_FORWARD); res = stepper_selected->runForward(); output_msg(MSG_RETURN_CODE); - Serial.println(res); + SerialInterface.println(res); return true; } break; @@ -1410,7 +1448,7 @@ bool process_cmd(char *cmd) { output_msg(MSG_RUN_BACKWARD); res = stepper_selected->runBackward(); output_msg(MSG_RETURN_CODE); - Serial.println(res); + SerialInterface.println(res); return true; } break; @@ -1450,7 +1488,7 @@ bool process_cmd(char *cmd) { while (stepper_selected->isRunning()) { // do nothing } - Serial.println("STOPPED"); + SerialInterface.println("STOPPED"); } #endif return true; @@ -1513,7 +1551,7 @@ bool process_cmd(char *cmd) { } if (get_val1_val2_val3(cmd) == 3) { output_msg(MSG_ATTACH_PULSE_COUNTER); - Serial.println(val_n[0]); + SerialInterface.println(val_n[0]); if (!stepper_selected->attachToPulseCounter(val_n[0], val_n[1], val_n[2])) { output_msg(MSG_ERROR_ATTACH_PULSE_COUNTER); @@ -1522,7 +1560,7 @@ bool process_cmd(char *cmd) { } if (get_val1_val2_val3(cmd) == 1) { output_msg(MSG_ATTACH_PULSE_COUNTER); - Serial.println(val_n[0]); + SerialInterface.println(val_n[0]); if (!stepper_selected->attachToPulseCounter(val_n[0])) { output_msg(MSG_ERROR_ATTACH_PULSE_COUNTER); } @@ -1536,7 +1574,7 @@ bool process_cmd(char *cmd) { const struct test_seq_def_s *ts = &test_sequence[i]; if (strcmp(out_buffer, ts->code) == 0) { output_msg(MSG_SELECT_TEST_SEQUENCE); - Serial.println(out_buffer); + SerialInterface.println(out_buffer); test_seq[selected].test = ts->test; test_seq[selected].state = 0; return true; @@ -1551,8 +1589,8 @@ bool process_cmd(char *cmd) { void loop() { char ch = 0; if (input == NULL) { - if (Serial.available()) { - ch = Serial.read(); + if (SerialInterface.available()) { + ch = SerialInterface.read(); } } else { ch = *input; @@ -1594,7 +1632,7 @@ void loop() { if (out_ptr > 0) { if (!process_cmd(out_buffer)) { output_msg(MSG_UNKNOWN_COMMAND); - Serial.println(out_buffer); + SerialInterface.println(out_buffer); } } out_ptr = 0; diff --git a/examples/StepperDemo/generic.h b/examples/StepperDemo/generic.h index d4154d96..47404d16 100644 --- a/examples/StepperDemo/generic.h +++ b/examples/StepperDemo/generic.h @@ -1,3 +1,8 @@ +#ifndef GENERIC_H +#define GENERIC_H + +#include + #if defined(ARDUINO_ARCH_AVR) #define get_char(x) pgm_read_byte(x) #define MSG_TYPE PGM_P @@ -7,3 +12,11 @@ #else #error "Unsupported derivate" #endif + +#if defined(CONFIG_IDF_TARGET_ESP32C3) && (ARDUINO_USB_MODE == 1) +#define SerialInterface USBSerial +#else +#define SerialInterface Serial +#endif + +#endif diff --git a/examples/StepperDemo/test_seq.h b/examples/StepperDemo/test_seq.h index 514e4f62..0dd79794 100644 --- a/examples/StepperDemo/test_seq.h +++ b/examples/StepperDemo/test_seq.h @@ -1,4 +1,6 @@ #include "FastAccelStepper.h" +#include "generic.h" + #define TEST_STATE_ERROR 0xffff struct test_seq_s { bool (*test)(FastAccelStepper *stepper, struct test_seq_s *, diff --git a/examples/StepperDemo/test_seq_07.cpp b/examples/StepperDemo/test_seq_07.cpp index f469a47a..f393f959 100644 --- a/examples/StepperDemo/test_seq_07.cpp +++ b/examples/StepperDemo/test_seq_07.cpp @@ -14,7 +14,7 @@ bool test_seq_07(FastAccelStepper *stepper, struct test_seq_s *seq, case 1: if ((stepper->rampState() & RAMP_STATE_MASK) == RAMP_STATE_COAST) { int32_t dt = time_ms - seq->u32_1; - Serial.println(dt); + SerialInterface.println(dt); // 779 esp, 805 avr (neu 810 avr), 820: esp32 with rmt, 812: esp32 with // rmt second channel if (abs(dt - 792) > 30) { @@ -43,11 +43,11 @@ bool test_seq_07(FastAccelStepper *stepper, struct test_seq_s *seq, case 4: if (!stepper->isRunning()) { int32_t dt = time_ms - seq->u32_1; - Serial.println(dt); + SerialInterface.println(dt); if (abs(dt - 1495) > 30) { seq->state = TEST_STATE_ERROR; } - Serial.println(stepper->getPositionAfterCommandsCompleted()); + SerialInterface.println(stepper->getPositionAfterCommandsCompleted()); if (stepper->getPositionAfterCommandsCompleted() != 0) { seq->state = TEST_STATE_ERROR; } diff --git a/examples/StepperDemo/test_seq_08.cpp b/examples/StepperDemo/test_seq_08.cpp index 9c034b59..239726b1 100644 --- a/examples/StepperDemo/test_seq_08.cpp +++ b/examples/StepperDemo/test_seq_08.cpp @@ -15,7 +15,7 @@ bool test_seq_08(FastAccelStepper *stepper, struct test_seq_s *seq, case 0: // INIT srand(135); if (!stepper->attachToPulseCounter(7)) { - Serial.println("Error attaching to pulse counter"); + SerialInterface.println("Error attaching to pulse counter"); seq->state = TEST_STATE_ERROR; return true; } @@ -27,10 +27,10 @@ bool test_seq_08(FastAccelStepper *stepper, struct test_seq_s *seq, int16_t pcnt = stepper->readPulseCounter(); int32_t spos = stepper->getPositionAfterCommandsCompleted(); if ((pcnt & 0x3fff) != (spos & 0x3fff)) { - Serial.print("stepper pos="); - Serial.print(spos); - Serial.print(" real pos="); - Serial.println(pcnt); + SerialInterface.print("stepper pos="); + SerialInterface.print(spos); + SerialInterface.print(" real pos="); + SerialInterface.println(pcnt); seq->state = TEST_STATE_ERROR; return true; @@ -69,12 +69,12 @@ bool test_seq_08(FastAccelStepper *stepper, struct test_seq_s *seq, move = -move; } - Serial.print("speed="); - Serial.print(speed); - Serial.print(" accel="); - Serial.print(accel); - Serial.print(" move="); - Serial.println(move); + SerialInterface.print("speed="); + SerialInterface.print(speed); + SerialInterface.print(" accel="); + SerialInterface.print(accel); + SerialInterface.print(" move="); + SerialInterface.println(move); stepper->setSpeedInUs(speed); stepper->setAcceleration(accel); stepper->move(move); diff --git a/examples/StepperDemo/test_seq_09.cpp b/examples/StepperDemo/test_seq_09.cpp index 8105cbfc..f84302c7 100644 --- a/examples/StepperDemo/test_seq_09.cpp +++ b/examples/StepperDemo/test_seq_09.cpp @@ -7,7 +7,7 @@ bool test_seq_09(FastAccelStepper *stepper, struct test_seq_s *seq, srand(135); #if defined(SUPPORT_ESP32_PULSE_COUNTER) if (!stepper->attachToPulseCounter(7)) { - Serial.println("Error attaching to pulse counter"); + SerialInterface.println("Error attaching to pulse counter"); seq->state = TEST_STATE_ERROR; return true; } @@ -28,10 +28,10 @@ bool test_seq_09(FastAccelStepper *stepper, struct test_seq_s *seq, uint32_t accel = rand() % (AMAX * 4); accel = accel >> ((accel % 4) + 2); accel = accel + AMIN; - Serial.print("speed="); - Serial.print(speed); - Serial.print(" accel="); - Serial.println(accel); + SerialInterface.print("speed="); + SerialInterface.print(speed); + SerialInterface.print(" accel="); + SerialInterface.println(accel); stepper->setSpeedInUs(speed); stepper->setAcceleration(accel); if (rand() & 1) { @@ -58,8 +58,8 @@ bool test_seq_09(FastAccelStepper *stepper, struct test_seq_s *seq, #if defined(SUPPORT_ESP32_PULSE_COUNTER) int16_t old = seq->s16_1; seq->s16_1 = stepper->readPulseCounter(); - Serial.print("Steps needed for stop="); - Serial.println(old - seq->s16_1); + SerialInterface.print("Steps needed for stop="); + SerialInterface.println(old - seq->s16_1); #endif seq->state++; } @@ -68,7 +68,7 @@ bool test_seq_09(FastAccelStepper *stepper, struct test_seq_s *seq, if (time_ms - seq->u32_1 >= 100) { #if defined(SUPPORT_ESP32_PULSE_COUNTER) if (seq->s16_1 != stepper->readPulseCounter()) { - Serial.println("Step AFTER stop"); + SerialInterface.println("Step AFTER stop"); } #endif seq->u32_1 = time_ms; diff --git a/examples/StepperDemo/test_seq_10.cpp b/examples/StepperDemo/test_seq_10.cpp index cf99f56e..d5c2ffbe 100644 --- a/examples/StepperDemo/test_seq_10.cpp +++ b/examples/StepperDemo/test_seq_10.cpp @@ -50,9 +50,9 @@ bool test_seq_10(FastAccelStepper *stepper, struct test_seq_s *seq, stepper->applySpeedAcceleration(); stepper->stopMove(); } else { - Serial.print("Speed changes 64us <=> "); - Serial.print(64 + seq->s16_1); - Serial.println("us"); + SerialInterface.print("Speed changes 64us <=> "); + SerialInterface.print(64 + seq->s16_1); + SerialInterface.println("us"); seq->state = 2; } } diff --git a/examples/StepperDemo/test_seq_11.cpp b/examples/StepperDemo/test_seq_11.cpp index 8f158084..4a91649a 100644 --- a/examples/StepperDemo/test_seq_11.cpp +++ b/examples/StepperDemo/test_seq_11.cpp @@ -28,16 +28,16 @@ bool test_seq_11(FastAccelStepper *stepper, struct test_seq_s *seq, for (uint16_t i = 0; i <= 1000; i++) { int32_t pos = stepper->getCurrentPosition(); if (pos < seq->s32_1) { - Serial.print("i="); - Serial.print(i); + SerialInterface.print("i="); + SerialInterface.print(i); if (i != 0) { - Serial.print(" prev pos="); - Serial.print(prev_pos); + SerialInterface.print(" prev pos="); + SerialInterface.print(prev_pos); } - Serial.print(" old pos="); - Serial.print(seq->s32_1); - Serial.print(" curr pos="); - Serial.println(pos); + SerialInterface.print(" old pos="); + SerialInterface.print(seq->s32_1); + SerialInterface.print(" curr pos="); + SerialInterface.println(pos); stepper->stopMove(); seq->state = TEST_STATE_ERROR; return true; @@ -54,16 +54,16 @@ bool test_seq_11(FastAccelStepper *stepper, struct test_seq_s *seq, for (uint16_t i = 0; i <= 1000; i++) { int32_t pos = stepper->getCurrentPosition(); if (pos > seq->s32_1) { - Serial.print("i="); - Serial.print(i); + SerialInterface.print("i="); + SerialInterface.print(i); if (i != 0) { - Serial.print(" prev pos="); - Serial.print(prev_pos); + SerialInterface.print(" prev pos="); + SerialInterface.print(prev_pos); } - Serial.print(" old pos="); - Serial.print(seq->s32_1); - Serial.print(" curr pos="); - Serial.println(pos); + SerialInterface.print(" old pos="); + SerialInterface.print(seq->s32_1); + SerialInterface.print(" curr pos="); + SerialInterface.println(pos); stepper->stopMove(); seq->state = TEST_STATE_ERROR; return true; diff --git a/examples/StepperDemo/test_seq_12.cpp b/examples/StepperDemo/test_seq_12.cpp index 1d718b0d..ef00127e 100644 --- a/examples/StepperDemo/test_seq_12.cpp +++ b/examples/StepperDemo/test_seq_12.cpp @@ -51,9 +51,9 @@ bool test_seq_12(FastAccelStepper *stepper, struct test_seq_s *seq, stepper->applySpeedAcceleration(); stepper->stopMove(); } else { - Serial.print("Speed changes 64us <=> "); - Serial.print(64 + seq->s16_1); - Serial.println("us"); + SerialInterface.print("Speed changes 64us <=> "); + SerialInterface.print(64 + seq->s16_1); + SerialInterface.println("us"); seq->state = 2; } } diff --git a/examples/StepperDemo/test_seq_13.cpp b/examples/StepperDemo/test_seq_13.cpp index c619de24..37a90d3d 100644 --- a/examples/StepperDemo/test_seq_13.cpp +++ b/examples/StepperDemo/test_seq_13.cpp @@ -18,8 +18,8 @@ bool test_seq_13(FastAccelStepper *stepper, struct test_seq_s *seq, case 3: res = stepper->addQueueEntry(&cmd_step); if (res > 1) { - Serial.print(res); - Serial.print(' '); + SerialInterface.print(res); + SerialInterface.print(' '); } else { seq->u32_1 = time_ms; seq->state++; @@ -28,7 +28,7 @@ bool test_seq_13(FastAccelStepper *stepper, struct test_seq_s *seq, case 4: if (time_ms - seq->u32_1 >= 20) { if (stepper->getCurrentPosition() != 4) { - Serial.println("not all raw commands executed"); + SerialInterface.println("not all raw commands executed"); seq->state = TEST_STATE_ERROR; } return true; diff --git a/extras/ci/platformio.ini b/extras/ci/platformio.ini index e4131fbe..0c59cb23 100644 --- a/extras/ci/platformio.ini +++ b/extras/ci/platformio.ini @@ -17,23 +17,167 @@ platform = espressif32 board = esp32dev framework = arduino -build_flags = -Werror -Wall -Wno-deprecated-declarations -Wno-error=incompatible-pointer-types +build_flags = -Wall board_build.f_cpu = 240000000L lib_extra_dirs = ../../.. -[env:esp32arduinolatest] -platform = espressif32 +[env:esp32_V6_6_0] +platform = espressif32 @ 6.6.0 board = esp32dev framework = arduino -build_flags = -Werror -Wall -Wno-deprecated-declarations -Wno-error=incompatible-pointer-types +build_flags = -Wall board_build.f_cpu = 240000000L lib_extra_dirs = ../../.. -[env:esp32arduinoV340] -platform = espressif32 @ 3.4.0 -board = esp32dev -framework = arduino -build_flags = -Werror -Wall -Wno-deprecated-declarations -Wno-error=incompatible-pointer-types +[env:esp32_V6_5_0] +platform = espressif32 @ 6.5.0 +board = esp32dev +framework = arduino +build_flags = -Wall +board_build.f_cpu = 240000000L +lib_extra_dirs = ../../.. + +[env:esp32_V6_4_0] +platform = espressif32 @ 6.4.0 +board = esp32dev +framework = arduino +build_flags = -Werror -Wall +board_build.f_cpu = 240000000L +lib_extra_dirs = ../../.. + +[env:esp32_V6_3_2] +platform = espressif32 @ 6.3.2 +board = esp32dev +framework = arduino +build_flags = -Werror -Wall +board_build.f_cpu = 240000000L +lib_extra_dirs = ../../.. + +[env:esp32_V6_2_0] +platform = espressif32 @ 6.2.0 +board = esp32dev +framework = arduino +build_flags = -Werror -Wall +board_build.f_cpu = 240000000L +lib_extra_dirs = ../../.. + +[env:esp32_V6_1_0] +platform = espressif32 @ 6.1.0 +board = esp32dev +framework = arduino +build_flags = -Werror -Wall +board_build.f_cpu = 240000000L +lib_extra_dirs = ../../.. + +[env:esp32_V6_0_1] +platform = espressif32 @ 6.0.1 +board = esp32dev +framework = arduino +build_flags = -Werror -Wall +board_build.f_cpu = 240000000L +lib_extra_dirs = ../../.. + +[env:esp32_V5_3_0] +platform = espressif32 @ 5.3.0 +board = esp32dev +framework = arduino +build_flags = -Werror -Wall +board_build.f_cpu = 240000000L +lib_extra_dirs = ../../.. + +[env:esp32_V5_2_0] +platform = espressif32 @ 5.2.0 +board = esp32dev +framework = arduino +build_flags = -Werror -Wall +board_build.f_cpu = 240000000L +lib_extra_dirs = ../../.. + +[env:esp32_V5_1_1] +platform = espressif32 @ 5.1.1 +board = esp32dev +framework = arduino +build_flags = -Werror -Wall +board_build.f_cpu = 240000000L +lib_extra_dirs = ../../.. + +[env:esp32_V5_0_0] +platform = espressif32 @ 5.0.0 +board = esp32dev +framework = arduino +build_flags = -Werror -Wall +board_build.f_cpu = 240000000L +lib_extra_dirs = ../../.. + +[env:esp32_V4_4_0] +platform = espressif32 @ 4.4.0 +board = esp32dev +framework = arduino +build_flags = -Werror -Wall +board_build.f_cpu = 240000000L +lib_extra_dirs = ../../.. + +[env:esp32_V4_3_0] +platform = espressif32 @ 4.3.0 +board = esp32dev +framework = arduino +build_flags = -Werror -Wall +board_build.f_cpu = 240000000L +lib_extra_dirs = ../../.. + +[env:esp32_V4_2_0] +platform = espressif32 @ 4.2.0 +board = esp32dev +framework = arduino +build_flags = -Werror -Wall +board_build.f_cpu = 240000000L +lib_extra_dirs = ../../.. + +[env:esp32_V4_1_0] +platform = espressif32 @ 4.1.0 +board = esp32dev +framework = arduino +build_flags = -Werror -Wall +board_build.f_cpu = 240000000L +lib_extra_dirs = ../../.. + +[env:esp32_V4_0_0_disabled] +platform = espressif32 @ 4.0.0 +board = esp32dev +framework = arduino +build_flags = -Werror -Wall +board_build.f_cpu = 240000000L +lib_extra_dirs = ../../.. + +[env:esp32_V3_5_0] +platform = espressif32 @ 3.5.0 +board = esp32dev +framework = arduino +build_flags = -Wall +board_build.f_cpu = 240000000L +lib_extra_dirs = ../../.. + +[env:esp32s2_V6_5_0] +platform = espressif32 @ 6.5.0 +board = esp32dev +framework = arduino +build_flags = -Wall +board_build.f_cpu = 240000000L +lib_extra_dirs = ../../.. + +[env:esp32s3_V6_5_0] +platform = espressif32 @ 6.5.0 +board = esp32dev +framework = arduino +build_flags = -Wall +board_build.f_cpu = 240000000L +lib_extra_dirs = ../../.. + +[env:esp32c3_V6_5_0] +platform = espressif32 @ 6.5.0 +board = esp32dev +framework = arduino +build_flags = -Wall board_build.f_cpu = 240000000L lib_extra_dirs = ../../.. @@ -65,10 +209,13 @@ lib_extra_dirs = ../../.. [env:esp32c3] board = esp32-c3-devkitm-1 framework = arduino -platform = https://github.com/tasmota/platform-espressif32/releases/download/v.2.0.3/platform-espressif32-v.2.0.3.zip +platform = espressif32 +#platform = https://github.com/tasmota/platform-espressif32/releases/download/2023.10.03/platform-espressif32.zip build_flags = -Werror -Wall -Wno-deprecated-declarations -Wno-error=incompatible-pointer-types board_build.f_cpu = 240000000L lib_extra_dirs = ../../.. +board_build.flash_mode = dio +upload_port = /dev/ttyACM0 [env:nanoatmega168] platform = atmelavr diff --git a/extras/doc/FastAccelStepper_API.md b/extras/doc/FastAccelStepper_API.md index 498b0808..97dfc231 100644 --- a/extras/doc/FastAccelStepper_API.md +++ b/extras/doc/FastAccelStepper_API.md @@ -64,7 +64,9 @@ hardware may have limitations - e.g. no stepper resources anymore, or the step pin cannot be used, then NULL is returned. So it is advised to check the return value of this call. ```cpp +#if !defined(SUPPORT_SELECT_DRIVER_TYPE) FastAccelStepper* stepperConnectToPin(uint8_t step_pin); +#endif ``` For e.g. esp32, there are two types of driver. One using mcpwm and pcnt module. And another using rmt module. @@ -74,7 +76,8 @@ This call allows to select the respective driver #define DRIVER_MCPWM_PCNT 0 #define DRIVER_RMT 1 #define DRIVER_DONT_CARE 2 - FastAccelStepper* stepperConnectToPin(uint8_t step_pin, uint8_t driver_type); + FastAccelStepper* stepperConnectToPin(uint8_t step_pin, + uint8_t driver_type = DRIVER_DONT_CARE); #endif ``` Comments to valid pins: @@ -157,8 +160,8 @@ And the two directions of a move #define RAMP_DIRECTION_COUNT_DOWN 64 ``` A ramp state value of 2 is set after any move call on a stopped motor -and until the stepper task. The stepper task will then control the direction -flags +and until the stepper task is serviced. The stepper task will then +control the direction flags ## Timing values - Architecture dependent @@ -290,6 +293,15 @@ For the device's maximum allowed speed, the following calls can be used. uint32_t getMaxSpeedInHz(); uint32_t getMaxSpeedInMilliHz(); ``` +For esp32 and avr, the device's maximum allowed speed can be overridden. +Allocating a new stepper will override any absolute speed limit. +This is absolutely untested, no error checking implemented. +Use at your own risk ! +```cpp +#if SUPPORT_UNSAFE_ABS_SPEED_LIMIT_SETTING == 1 + void setAbsoluteSpeedLimit(uint16_t max_speed_in_ticks); +#endif +``` Setting the speed can be done with the four `setSpeed...()` calls. The new value will be used only after call of these functions: @@ -326,9 +338,22 @@ retrieves the actual speed. | > 0 | while position counting up  | | < 0 | while position counting down | +If the parameter realtime is true, then the most actual speed +from the stepper queue is derived. This works only, if the queue +does not contain pauses, which is normally the case for slow speeds. +Otherwise the speed from the ramp generator is reported, which is +done always in case of `realtime == false`. That speed is typically +the value of the speed a couple of milliseconds later. + +The drawback of `realtime == true` is, that the reported speed +may either come from the queue or from the ramp generator. +This means the returned speed may have jumps during +acceleration/deceleration. + +For backward compatibility, the default is true. ```cpp - int32_t getCurrentSpeedInUs(); - int32_t getCurrentSpeedInMilliHz(); + int32_t getCurrentSpeedInUs(bool realtime = true); + int32_t getCurrentSpeedInMilliHz(bool realtime = true); ``` ## Acceleration setAcceleration() expects as parameter the change of speed @@ -488,6 +513,39 @@ In keep running mode, the targetPos() is not updated ```cpp int32_t targetPos() { return _rg.targetPosition(); } ``` +The stepper task adds commands to the stepper queue until +either at least two commands are planned, or the commands +cover sufficient time into the future. Default value for that time is 20ms. + +The stepper task is cyclically executed every ~4ms. +Especially for avr, the step interrupts puts a significant load on the uC, +so the cyclical stepper task can even run for 2-3 ms. On top of that, +other interrupts caused by the application could increase the load even further. + +Consequently, the forward planning should fill the queue for ideally two cycles, +this means 8ms. This means, the default 20ms provide a sufficient margin and +even a missed cycle is not an issue. + +The drawback of the 20ms is, that any change in speed/acceleration are added after +those 20ms and for an application, requiring fast reaction times, this may +impact the expected performance. + +Due to this the forward planning time can be adjusted with the following API call +for each stepper individually. + +Attention: +- This is only for advanced users: no error checking is implemented. +- Only change the forward planning time, if the stepper is not running. +- Too small values bear the risk of a stepper running at full speed suddenly stopping + due to lack of commands in the queue. +```cpp + void setForwardPlanningTimeInMs(uint8_t ms) { + _forward_planning_in_ticks = ms; +``` + _forward_planning_in_ticks *= TICKS_PER_S / 1000;ticks per ms +```cpp + } +``` ## Low Level Stepper Queue Management (low level access) If the queue is already running, then the start parameter is obsolote. diff --git a/extras/scripts/build-workflows.py b/extras/scripts/build-workflows.py new file mode 100755 index 00000000..9eb00228 --- /dev/null +++ b/extras/scripts/build-workflows.py @@ -0,0 +1,51 @@ +#!/usr/bin/env python3 + +import configparser + +fname = "../ci/platformio.ini" +action_dirs = "../../.github/workflows/" + +template = """ +name: Build examples for {derivate} @ {version} + +on: + push: + branches: [ master ] + pull_request: + branches: [ master ] + +jobs: + build: + + runs-on: ubuntu-latest + + steps: + - name: Checkout + uses: actions/checkout@v3 + - name: Make directories + run: bash extras/scripts/build-pio-dirs.sh + - name: Build on PlatformIO + run: bash extras/scripts/build-platformio.sh {derivate}_{version} +""" + +# Create a ConfigParser object +config = configparser.ConfigParser() + +# Read the INI file +config.read(fname) + +# Loop through sections +for section in config.sections(): + s = section.replace("env:","") + flds = s.split("_") + derivate = flds[0] + version = s.replace(derivate + "_","") + if "disabled" in s: + print(f"Skip: {derivate} {version}") + continue + if version[0] == "V": + print(f"Section: {derivate} {version}") + action = template.format(derivate=derivate,version=version) + fname = f"build_examples_{derivate}_{version}.yml" + with open(action_dirs + fname,"w") as fp: + fp.write(action) diff --git a/extras/tests/pc_based/Makefile b/extras/tests/pc_based/Makefile index 839452a3..6787c2a7 100644 --- a/extras/tests/pc_based/Makefile +++ b/extras/tests/pc_based/Makefile @@ -13,7 +13,7 @@ test: $(TESTS) pmf_test rmc_test $(addsuffix >>test.log &&,$(addprefix ./,$(TESTS))) echo "All tests passed" LIB_H=FastAccelStepper.h PoorManFloat.h StepperISR.h \ - RampGenerator.h RampConstAcceleration.h RampCalculator.h common.h + RampGenerator.h RampConstAcceleration.h RampCalculator.h fas_common.h LIB_O=FastAccelStepper.o PoorManFloat.o StepperISR_test.o \ RampGenerator.o RampConstAcceleration.o RampCalculator.o StepperISR.o diff --git a/extras/tests/pc_based/off_test_15.cpp b/extras/tests/pc_based/off_test_15.cpp new file mode 100644 index 00000000..f2815a05 --- /dev/null +++ b/extras/tests/pc_based/off_test_15.cpp @@ -0,0 +1,124 @@ +#include +#include +#include + +#include "FastAccelStepper.h" +#include "StepperISR.h" + +char TCCR1A; +char TCCR1B; +char TCCR1C; +char TIMSK1; +char TIFR1; +unsigned short OCR1A; +unsigned short OCR1B; + +StepperQueue fas_queue[NUM_QUEUES]; + +void inject_fill_interrupt(int mark) {} +void noInterrupts() {} +void interrupts() {} + +#include "RampChecker.h" + +class FastAccelStepperTest { + public: + void init_queue() { + fas_queue[0].read_idx = 0; + fas_queue[1].read_idx = 0; + fas_queue[0].next_write_idx = 0; + fas_queue[1].next_write_idx = 0; + } + + void ramp() { + init_queue(); + FastAccelStepper s = FastAccelStepper(); + s.init(NULL, 0, 0); + RampChecker rc = RampChecker(); + assert(0 == s.getCurrentPosition()); + + assert(s.isQueueEmpty()); + s.setSpeedInHz(36800); + s.setAcceleration(1000000); + s.fill_queue(); + assert(s.isQueueEmpty()); + float old_planned_time_in_buffer = 0; + + char fname[100]; + sprintf(fname, "test_15.gnuplot"); + rc.start_plot(fname); + s.runForward(); + int32_t wait_ticks = TICKS_PER_S / 10; + uint8_t state = 0; + for (int i = 0; i < 2000; i++) { + if ((state == 0) && (wait_ticks < rc.total_ticks)) { + printf("New move\n"); + s.move(-100000); + wait_ticks += TICKS_PER_S / 10; + state += 1; + } + if ((state == 1) && (wait_ticks < rc.total_ticks)) { + printf("move with changed acceleration\n"); + s.setAcceleration(5000); + s.move(100000); + wait_ticks += TICKS_PER_S / 10; + state += 1; + } + if ((state == 2) && (wait_ticks < rc.total_ticks)) { + printf("stop"); + s.stopMove(); + wait_ticks += 2 * TICKS_PER_S / 10; + state += 1; + } + if (true) { + printf( + "Loop %d: Queue read/write = %d/%d Target pos = %d, Queue End " + "pos = %d QueueEmpty=%s\n", + i, fas_queue[0].read_idx, fas_queue[0].next_write_idx, + s.targetPos(), s.getPositionAfterCommandsCompleted(), + s.isQueueEmpty() ? "yes" : "no"); + } + if (!s.isRampGeneratorActive()) { + break; + } + s.fill_queue(); + if ((state == 3) && (wait_ticks < rc.total_ticks)) { + break; + } + uint32_t from_dt = rc.total_ticks; + while (!s.isQueueEmpty()) { + rc.increase_ok = true; + rc.decrease_ok = true; + rc.check_section( + &fas_queue[0].entry[fas_queue[0].read_idx & QUEUE_LEN_MASK]); + fas_queue[0].read_idx++; + } + uint32_t to_dt = rc.total_ticks; + float planned_time = (to_dt - from_dt) * 1.0 / 16000000; + printf("planned time in buffer: %.6fs\n", planned_time); + // This must be ensured, so that the stepper does not run out of + // commands + assert((i == 0) || (old_planned_time_in_buffer > 0.005)); + old_planned_time_in_buffer = planned_time; + // stop after + if (rc.total_ticks > TICKS_PER_S * 40) { + break; + } + } + rc.finish_plot(); + // test(!s.isRampGeneratorActive(), "too many commands created"); + test(s.getCurrentPosition() > 70000, "stepper runs too slow"); + test(s.getCurrentPosition() < 80000, "stepper runs too fast"); + printf("Total time %f\n", rc.total_ticks / 16000000.0); + +#if (TEST_CREATE_QUEUE_CHECKSUM == 1) + printf("CHECKSUM for %d/%d/%d: %d\n", steps, travel_dt, accel, s.checksum); +#endif + } +}; +int main() { + FastAccelStepperTest test; + test.ramp(); + printf("TEST_15 PASSED\n"); + return 0; +} diff --git a/extras/tests/simavr_based/.gitignore b/extras/tests/simavr_based/.gitignore new file mode 100644 index 00000000..8089a5ac --- /dev/null +++ b/extras/tests/simavr_based/.gitignore @@ -0,0 +1,2 @@ +.links +.makefiles diff --git a/extras/tests/simavr_based/Makefile b/extras/tests/simavr_based/Makefile index 44454b2e..b8502ba0 100644 --- a/extras/tests/simavr_based/Makefile +++ b/extras/tests/simavr_based/Makefile @@ -19,15 +19,21 @@ pmf: externalCall: make -C test_externalCall -%/.tested: $(SRC) run_avr %/expect.txt %/platformio.ini +%/.tested: $(SRC) run_avr %/expect.txt %/platformio.ini .makefiles .links make SILENCE=$(SILENCE) -C $(dir $@) +.makefiles: makefiles + makefiles: $(addsuffix /Makefile,$(TESTS)) + touch .makefiles %/Makefile: cd $(dir $@); ln -s ../Makefile.test Makefile +.links: links + links: $(SD_SRC_DIRS) + touch .links %/src/.dir: mkdir -p $(dir $@) @@ -82,5 +88,5 @@ clean: rm -fR */.pio */.tested */x.vcd */result.txt find . -type l -delete find . -type d -empty -delete - make links makefiles + rm -f .links .makefiles diff --git a/extras/tests/simavr_based/Makefile.test b/extras/tests/simavr_based/Makefile.test index 6b24eeae..f621550b 100644 --- a/extras/tests/simavr_based/Makefile.test +++ b/extras/tests/simavr_based/Makefile.test @@ -87,7 +87,7 @@ else ifeq ($(DEVICE),$(filter $(DEVICE),atmega168 atmega168p atmega328 atmega328 TRACES+=-at DirA=trace@0x2b/0x20 # Pin 5 PD5 TRACES+=-at DirB=trace@0x2b/0x80 # Pin 7 PD7 TRACES+=-at EnableA=trace@0x2b/0x40 # Pin 6 PD6 -TRACES+=-at EnableB=trace@0x25/0x01 # Pin 8 PB0 +TRACES+=-at EnableB=trace@0x25/0x01 # Pin 0 PB0 else ifeq ($(DUT),atmega32u4) TRACES+=-at DirA=trace@0x25/0x10 # Pin 26 PB4 diff --git a/extras/tests/simavr_based/judge_pos0.awk b/extras/tests/simavr_based/judge_pos0.awk new file mode 100644 index 00000000..db0488ca --- /dev/null +++ b/extras/tests/simavr_based/judge_pos0.awk @@ -0,0 +1,22 @@ +BEGIN { + ok = 0 +} + +FNR == NR { + # result.txt + lines[FNR] = $0 +} + +/^Position\[A\]/ { + print +} +$0 == "Position[A]=0" { + ok = 1 +} + +END { + if (ok == 1) { + print("PASS") + print("PASS") > ".tested" + } +} diff --git a/extras/tests/simavr_based/test_issue208/.gitignore b/extras/tests/simavr_based/test_issue208/.gitignore new file mode 100644 index 00000000..8eba6c8d --- /dev/null +++ b/extras/tests/simavr_based/test_issue208/.gitignore @@ -0,0 +1 @@ +src/ diff --git a/extras/tests/simavr_based/test_issue208/Makefile b/extras/tests/simavr_based/test_issue208/Makefile new file mode 100644 index 00000000..d57f9fb6 --- /dev/null +++ b/extras/tests/simavr_based/test_issue208/Makefile @@ -0,0 +1,132 @@ +# +# In order to execute the test for one directory use: +# +# make -C test_sd_01b_328p -f ../Makefile.test + +SRC=$(wildcard ../../../src/*) $(wildcard src/*) + +# platformio should contain only one env section. +# This section states the dut name +# atmega168 +# atmega168p +# atmega328 +# atmega328p +# atmega2560_timer1 +# atmega2560_timer3 +# atmega2560_timer4 +# atmega2560_timer5 +# + +DUT=$(shell gawk '/env:/{print(substr($$1,6,length($$1)-6))}' platformio.ini) + +TRACES=-at StepISR=trace@0x25/0x08 # PB3 +TRACES+=-at FillISR=trace@0x25/0x10 # PB4 + +# +ifeq ($(DUT),atmega2560_timer1) +DEVICE=atmega2560 +TRACES+=-at StepA=trace@0x025/0x20 #OC1A PB5 11 ATMega2560 +TRACES+=-at StepB=trace@0x025/0x40 #OC1B PB6 12 ATMega2560 +TRACES+=-at StepC=trace@0x025/0x80 #OC1C PB7 13 ATMega2560 +# +else ifeq ($(DUT),atmega2560_timer3) +DEVICE=atmega2560 +TRACES+=-at StepA=trace@0x02e/0x08 #OC3A PE3 5 ATMega2560 +TRACES+=-at StepB=trace@0x02e/0x10 #OC3B PE4 2 ATMega2560 +TRACES+=-at StepC=trace@0x02e/0x20 #OC3C PE5 3 ATMega2560 +# +else ifeq ($(DUT),atmega2560_timer4) +DEVICE=atmega2560 +TRACES+=-at StepA=trace@0x102/0x08 #OC4A PH3 6 ATMega2560 +TRACES+=-at StepB=trace@0x102/0x10 #OC4B PH4 7 ATMega2560 +TRACES+=-at StepC=trace@0x102/0x20 #OC4C PH5 8 ATMega2560 +# +else ifeq ($(DUT),atmega2560_timer5) +DEVICE=atmega2560 +TRACES+=-at StepA=trace@0x10b/0x08 #OC5A PL3 46 ATMega2560 +TRACES+=-at StepB=trace@0x10b/0x10 #OC5B PL4 45 ATMega2560 +TRACES+=-at StepC=trace@0x10b/0x20 #OC5C PL5 44 ATMega2560 + +else ifeq ($(DUT),atmega168) +DEVICE=atmega168 +TRACES+=-at StepA=trace@0x25/0x02 #OC1A PB1 9 atmega168 +TRACES+=-at StepB=trace@0x25/0x04 #OC1B PB2 10 atmega168 + +else ifeq ($(DUT),atmega168p) +DEVICE=atmega168p +TRACES+=-at StepA=trace@0x25/0x02 #OC1A PB1 9 atmega168p +TRACES+=-at StepB=trace@0x25/0x04 #OC1B PB2 10 atmega168p + +else ifeq ($(DUT),atmega328) +DEVICE=atmega328 +TRACES+=-at StepA=trace@0x25/0x02 #OC1A PB1 9 ATMega328 +TRACES+=-at StepB=trace@0x25/0x04 #OC1B PB2 10 ATMega328 + +else ifeq ($(DUT),atmega328p) +DEVICE=atmega328p +TRACES+=-at StepA=trace@0x25/0x02 #OC1A PB1 9 ATMega328p +TRACES+=-at StepB=trace@0x25/0x04 #OC1B PB2 10 ATMega328p + +else ifeq ($(DUT),atmega32u4) +DEVICE=atmega32u4 +TRACES+=-at StepA=trace@0x025/0x20 #OC1A PB5 11 +TRACES+=-at StepB=trace@0x025/0x40 #OC1B PB6 12 +#TRACES+=-at StepC=trace@0x025/0x80 #OC1C PB7 13 + +endif + +ifeq ($(DEVICE),atmega2560) +TRACES+=-at DirA=trace@0x2b/0x01 # Pin 21 PD0 +TRACES+=-at DirB=trace@0x2b/0x02 # Pin 20 PD1 +TRACES+=-at DirC=trace@0x10b/0x80 # Pin 42 PL7 +TRACES+=-at EnableA=trace@0x2b/0x04 # Pin 19 PD2 +TRACES+=-at EnableB=trace@0x2b/0x08 # Pin 18 PD3 +TRACES+=-at EnableC=trace@0x10b/0x40 # Pin 43 PL6 + +else ifeq ($(DEVICE),$(filter $(DEVICE),atmega168 atmega168p atmega328 atmega328p)) +TRACES+=-at DirA=trace@0x2b/0x20 # Pin 5 PD5 +TRACES+=-at DirB=trace@0x2b/0x80 # Pin 7 PD7 +TRACES+=-at EnableA=trace@0x2b/0x40 # Pin 6 PD6 +TRACES+=-at EnableB=trace@0x25/0x01 # Pin 8 PB0 + +else ifeq ($(DUT),atmega32u4) +TRACES+=-at DirA=trace@0x25/0x10 # Pin 26 PB4 +TRACES+=-at DirB=trace@0x25/0x08 # Pin 14 PB3 +#TRACES+=-at DirC=trace@0x10b/0x80 # Pin 42 PL7 +TRACES+=-at EnableA=trace@0x25/0x04 # Pin 16 PB2 +TRACES+=-at EnableB=trace@0x25/0x02 # Pin 15 PB1 +#TRACES+=-at EnableC=trace@0x10b/0x40 # Pin 43 PL6 + +endif + +FIRMWARE=".pio/build/$(DUT)/firmware.elf" + +DIR=$(shell env pwd) + +ifndef SILENCE + SILENCE=0 +endif + +test: .tested + +.tested: result.txt expect.txt ../judge.awk + echo DUT=$(DUT) + rm -f .tested + gawk -f ../judge.awk -v DIR=$(DIR) result.txt expect.txt + test -f .tested + +result.txt: x.vcd + gawk -v SILENCE=$(SILENCE) -f ../eval.awk x.vcd >/dev/null + cat expect.txt + +x.vcd: $(SRC) ../run_avr platformio.ini src/Issue208.ino + ~/.platformio/penv/bin/pio run -e $(DUT) || ~/.local/bin/pio run -e $(DUT) || env pio run -e $(DUT) + ../run_avr $(FIRMWARE) -m $(DEVICE) -o x.vcd $(TRACES) + +src/Issue208.ino: + mkdir -p src + cd src; ln -s ../../../../../examples/Issue208/Issue208.ino . + +clean: + rm -fR .pio .tested x.vcd result.txt + diff --git a/extras/tests/simavr_based/test_issue208/expect.txt b/extras/tests/simavr_based/test_issue208/expect.txt new file mode 100644 index 00000000..6cd81dbf --- /dev/null +++ b/extras/tests/simavr_based/test_issue208/expect.txt @@ -0,0 +1,18 @@ + DirA: 0*L->H, 1*H->L + DirB: 1*L->H, 0*H->L + EnableA: 0*L->H, 0*H->L + EnableB: 0*L->H, 0*H->L + StepA: 235908*L->H, 235908*H->L, Max High=11us Total High=927312us + StepB: 2*L->H, 2*H->L, Max High=12us Total High=17us +Position[A]=37462 + +Position[B]=2 + +Time in FillISR max=767 us, total=1211908 us + +Time in StepA max=11 us, total=927312 us + +Time in StepB max=12 us, total=17 us + +Time in StepISR max=6 us, total=897842 us + diff --git a/extras/tests/simavr_based/test_issue208/platformio.ini b/extras/tests/simavr_based/test_issue208/platformio.ini new file mode 100644 index 00000000..9eae37d7 --- /dev/null +++ b/extras/tests/simavr_based/test_issue208/platformio.ini @@ -0,0 +1,31 @@ +; 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 + +[platformio] + +# There should be only one env section for the DUT under test. +# One of +# atmega168p +# atmega328p +# atmega2560_timer1 +# atmega2560_timer3 +# atmega2560_timer4 +# atmega2560_timer5 +# +[common] +# This is the line input to StepperDemo: +build_flags = -D SIMULATOR -D SIMAVR_TIME_MEASUREMENT + +[env:atmega328p] +platform = atmelavr +board = nanoatmega328 +framework = arduino +build_flags = -Werror -Wall ${common.build_flags} +lib_extra_dirs = ../../../../.. diff --git a/extras/tests/simavr_based/test_issue250/.gitignore b/extras/tests/simavr_based/test_issue250/.gitignore new file mode 100644 index 00000000..8eba6c8d --- /dev/null +++ b/extras/tests/simavr_based/test_issue250/.gitignore @@ -0,0 +1 @@ +src/ diff --git a/extras/tests/simavr_based/test_issue250/Makefile b/extras/tests/simavr_based/test_issue250/Makefile new file mode 100644 index 00000000..ba9091d3 --- /dev/null +++ b/extras/tests/simavr_based/test_issue250/Makefile @@ -0,0 +1,131 @@ +# +# In order to execute the test for one directory use: +# +# make -C test_sd_01b_328p -f ../Makefile.test + +SRC=$(wildcard ../../../src/*) $(wildcard src/*) + +# platformio should contain only one env section. +# This section states the dut name +# atmega168 +# atmega168p +# atmega328 +# atmega328p +# atmega2560_timer1 +# atmega2560_timer3 +# atmega2560_timer4 +# atmega2560_timer5 +# + +DUT=$(shell gawk '/env:/{print(substr($$1,6,length($$1)-6))}' platformio.ini) + +TRACES=-at StepISR=trace@0x25/0x08 # PB3 +TRACES+=-at FillISR=trace@0x25/0x10 # PB4 + +# +ifeq ($(DUT),atmega2560_timer1) +DEVICE=atmega2560 +TRACES+=-at StepA=trace@0x025/0x20 #OC1A PB5 11 ATMega2560 +TRACES+=-at StepB=trace@0x025/0x40 #OC1B PB6 12 ATMega2560 +TRACES+=-at StepC=trace@0x025/0x80 #OC1C PB7 13 ATMega2560 +# +else ifeq ($(DUT),atmega2560_timer3) +DEVICE=atmega2560 +TRACES+=-at StepA=trace@0x02e/0x08 #OC3A PE3 5 ATMega2560 +TRACES+=-at StepB=trace@0x02e/0x10 #OC3B PE4 2 ATMega2560 +TRACES+=-at StepC=trace@0x02e/0x20 #OC3C PE5 3 ATMega2560 +# +else ifeq ($(DUT),atmega2560_timer4) +DEVICE=atmega2560 +TRACES+=-at StepA=trace@0x102/0x08 #OC4A PH3 6 ATMega2560 +TRACES+=-at StepB=trace@0x102/0x10 #OC4B PH4 7 ATMega2560 +TRACES+=-at StepC=trace@0x102/0x20 #OC4C PH5 8 ATMega2560 +# +else ifeq ($(DUT),atmega2560_timer5) +DEVICE=atmega2560 +TRACES+=-at StepA=trace@0x10b/0x08 #OC5A PL3 46 ATMega2560 +TRACES+=-at StepB=trace@0x10b/0x10 #OC5B PL4 45 ATMega2560 +TRACES+=-at StepC=trace@0x10b/0x20 #OC5C PL5 44 ATMega2560 + +else ifeq ($(DUT),atmega168) +DEVICE=atmega168 +TRACES+=-at StepA=trace@0x25/0x02 #OC1A PB1 9 atmega168 +TRACES+=-at StepB=trace@0x25/0x04 #OC1B PB2 10 atmega168 + +else ifeq ($(DUT),atmega168p) +DEVICE=atmega168p +TRACES+=-at StepA=trace@0x25/0x02 #OC1A PB1 9 atmega168p +TRACES+=-at StepB=trace@0x25/0x04 #OC1B PB2 10 atmega168p + +else ifeq ($(DUT),atmega328) +DEVICE=atmega328 +TRACES+=-at StepA=trace@0x25/0x02 #OC1A PB1 9 ATMega328 +TRACES+=-at StepB=trace@0x25/0x04 #OC1B PB2 10 ATMega328 + +else ifeq ($(DUT),atmega328p) +DEVICE=atmega328p +TRACES+=-at StepA=trace@0x25/0x02 #OC1A PB1 9 ATMega328p +TRACES+=-at StepB=trace@0x25/0x04 #OC1B PB2 10 ATMega328p + +else ifeq ($(DUT),atmega32u4) +DEVICE=atmega32u4 +TRACES+=-at StepA=trace@0x025/0x20 #OC1A PB5 11 +TRACES+=-at StepB=trace@0x025/0x40 #OC1B PB6 12 +#TRACES+=-at StepC=trace@0x025/0x80 #OC1C PB7 13 + +endif + +ifeq ($(DEVICE),atmega2560) +TRACES+=-at DirA=trace@0x2b/0x01 # Pin 21 PD0 +TRACES+=-at DirB=trace@0x2b/0x02 # Pin 20 PD1 +TRACES+=-at DirC=trace@0x10b/0x80 # Pin 42 PL7 +TRACES+=-at EnableA=trace@0x2b/0x04 # Pin 19 PD2 +TRACES+=-at EnableB=trace@0x2b/0x08 # Pin 18 PD3 +TRACES+=-at EnableC=trace@0x10b/0x40 # Pin 43 PL6 + +else ifeq ($(DEVICE),$(filter $(DEVICE),atmega168 atmega168p atmega328 atmega328p)) +TRACES+=-at DirA=trace@0x2b/0x20 # Pin 5 PD5 +TRACES+=-at DirB=trace@0x2b/0x80 # Pin 7 PD7 +TRACES+=-at EnableA=trace@0x2b/0x40 # Pin 6 PD6 +TRACES+=-at EnableB=trace@0x25/0x01 # Pin 8 PB0 + +else ifeq ($(DUT),atmega32u4) +TRACES+=-at DirA=trace@0x25/0x10 # Pin 26 PB4 +TRACES+=-at DirB=trace@0x25/0x08 # Pin 14 PB3 +#TRACES+=-at DirC=trace@0x10b/0x80 # Pin 42 PL7 +TRACES+=-at EnableA=trace@0x25/0x04 # Pin 16 PB2 +TRACES+=-at EnableB=trace@0x25/0x02 # Pin 15 PB1 +#TRACES+=-at EnableC=trace@0x10b/0x40 # Pin 43 PL6 + +endif + +FIRMWARE=".pio/build/$(DUT)/firmware.elf" + +DIR=$(shell env pwd) + +ifndef SILENCE + SILENCE=0 +endif + +test: .tested + +.tested: result.txt ../judge_pos0.awk + echo DUT=$(DUT) + rm -f .tested + gawk -f ../judge_pos0.awk -v DIR=$(DIR) result.txt + test -f .tested + +result.txt: x.vcd + gawk -v SILENCE=$(SILENCE) -f ../eval.awk x.vcd >/dev/null + +x.vcd: $(SRC) ../run_avr platformio.ini src/Issue250.ino + ~/.platformio/penv/bin/pio run -e $(DUT) || ~/.local/bin/pio run -e $(DUT) || env pio run -e $(DUT) + ../run_avr $(FIRMWARE) -m $(DEVICE) -o x.vcd $(TRACES) + +src/Issue250.ino: + mkdir -p src + cd src; ln -s ../../../../../examples/Issue250/Issue250.ino . + +clean: + rm -fR .pio .tested x.vcd result.txt + diff --git a/extras/tests/simavr_based/test_issue250/expect.txt b/extras/tests/simavr_based/test_issue250/expect.txt new file mode 100644 index 00000000..e69de29b diff --git a/extras/tests/simavr_based/test_issue250/platformio.ini b/extras/tests/simavr_based/test_issue250/platformio.ini new file mode 100644 index 00000000..9eae37d7 --- /dev/null +++ b/extras/tests/simavr_based/test_issue250/platformio.ini @@ -0,0 +1,31 @@ +; 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 + +[platformio] + +# There should be only one env section for the DUT under test. +# One of +# atmega168p +# atmega328p +# atmega2560_timer1 +# atmega2560_timer3 +# atmega2560_timer4 +# atmega2560_timer5 +# +[common] +# This is the line input to StepperDemo: +build_flags = -D SIMULATOR -D SIMAVR_TIME_MEASUREMENT + +[env:atmega328p] +platform = atmelavr +board = nanoatmega328 +framework = arduino +build_flags = -Werror -Wall ${common.build_flags} +lib_extra_dirs = ../../../../.. diff --git a/extras/tests/simavr_based/test_issue250_30us/.gitignore b/extras/tests/simavr_based/test_issue250_30us/.gitignore new file mode 100644 index 00000000..8eba6c8d --- /dev/null +++ b/extras/tests/simavr_based/test_issue250_30us/.gitignore @@ -0,0 +1 @@ +src/ diff --git a/extras/tests/simavr_based/test_issue250_30us/Makefile b/extras/tests/simavr_based/test_issue250_30us/Makefile new file mode 100644 index 00000000..ba9091d3 --- /dev/null +++ b/extras/tests/simavr_based/test_issue250_30us/Makefile @@ -0,0 +1,131 @@ +# +# In order to execute the test for one directory use: +# +# make -C test_sd_01b_328p -f ../Makefile.test + +SRC=$(wildcard ../../../src/*) $(wildcard src/*) + +# platformio should contain only one env section. +# This section states the dut name +# atmega168 +# atmega168p +# atmega328 +# atmega328p +# atmega2560_timer1 +# atmega2560_timer3 +# atmega2560_timer4 +# atmega2560_timer5 +# + +DUT=$(shell gawk '/env:/{print(substr($$1,6,length($$1)-6))}' platformio.ini) + +TRACES=-at StepISR=trace@0x25/0x08 # PB3 +TRACES+=-at FillISR=trace@0x25/0x10 # PB4 + +# +ifeq ($(DUT),atmega2560_timer1) +DEVICE=atmega2560 +TRACES+=-at StepA=trace@0x025/0x20 #OC1A PB5 11 ATMega2560 +TRACES+=-at StepB=trace@0x025/0x40 #OC1B PB6 12 ATMega2560 +TRACES+=-at StepC=trace@0x025/0x80 #OC1C PB7 13 ATMega2560 +# +else ifeq ($(DUT),atmega2560_timer3) +DEVICE=atmega2560 +TRACES+=-at StepA=trace@0x02e/0x08 #OC3A PE3 5 ATMega2560 +TRACES+=-at StepB=trace@0x02e/0x10 #OC3B PE4 2 ATMega2560 +TRACES+=-at StepC=trace@0x02e/0x20 #OC3C PE5 3 ATMega2560 +# +else ifeq ($(DUT),atmega2560_timer4) +DEVICE=atmega2560 +TRACES+=-at StepA=trace@0x102/0x08 #OC4A PH3 6 ATMega2560 +TRACES+=-at StepB=trace@0x102/0x10 #OC4B PH4 7 ATMega2560 +TRACES+=-at StepC=trace@0x102/0x20 #OC4C PH5 8 ATMega2560 +# +else ifeq ($(DUT),atmega2560_timer5) +DEVICE=atmega2560 +TRACES+=-at StepA=trace@0x10b/0x08 #OC5A PL3 46 ATMega2560 +TRACES+=-at StepB=trace@0x10b/0x10 #OC5B PL4 45 ATMega2560 +TRACES+=-at StepC=trace@0x10b/0x20 #OC5C PL5 44 ATMega2560 + +else ifeq ($(DUT),atmega168) +DEVICE=atmega168 +TRACES+=-at StepA=trace@0x25/0x02 #OC1A PB1 9 atmega168 +TRACES+=-at StepB=trace@0x25/0x04 #OC1B PB2 10 atmega168 + +else ifeq ($(DUT),atmega168p) +DEVICE=atmega168p +TRACES+=-at StepA=trace@0x25/0x02 #OC1A PB1 9 atmega168p +TRACES+=-at StepB=trace@0x25/0x04 #OC1B PB2 10 atmega168p + +else ifeq ($(DUT),atmega328) +DEVICE=atmega328 +TRACES+=-at StepA=trace@0x25/0x02 #OC1A PB1 9 ATMega328 +TRACES+=-at StepB=trace@0x25/0x04 #OC1B PB2 10 ATMega328 + +else ifeq ($(DUT),atmega328p) +DEVICE=atmega328p +TRACES+=-at StepA=trace@0x25/0x02 #OC1A PB1 9 ATMega328p +TRACES+=-at StepB=trace@0x25/0x04 #OC1B PB2 10 ATMega328p + +else ifeq ($(DUT),atmega32u4) +DEVICE=atmega32u4 +TRACES+=-at StepA=trace@0x025/0x20 #OC1A PB5 11 +TRACES+=-at StepB=trace@0x025/0x40 #OC1B PB6 12 +#TRACES+=-at StepC=trace@0x025/0x80 #OC1C PB7 13 + +endif + +ifeq ($(DEVICE),atmega2560) +TRACES+=-at DirA=trace@0x2b/0x01 # Pin 21 PD0 +TRACES+=-at DirB=trace@0x2b/0x02 # Pin 20 PD1 +TRACES+=-at DirC=trace@0x10b/0x80 # Pin 42 PL7 +TRACES+=-at EnableA=trace@0x2b/0x04 # Pin 19 PD2 +TRACES+=-at EnableB=trace@0x2b/0x08 # Pin 18 PD3 +TRACES+=-at EnableC=trace@0x10b/0x40 # Pin 43 PL6 + +else ifeq ($(DEVICE),$(filter $(DEVICE),atmega168 atmega168p atmega328 atmega328p)) +TRACES+=-at DirA=trace@0x2b/0x20 # Pin 5 PD5 +TRACES+=-at DirB=trace@0x2b/0x80 # Pin 7 PD7 +TRACES+=-at EnableA=trace@0x2b/0x40 # Pin 6 PD6 +TRACES+=-at EnableB=trace@0x25/0x01 # Pin 8 PB0 + +else ifeq ($(DUT),atmega32u4) +TRACES+=-at DirA=trace@0x25/0x10 # Pin 26 PB4 +TRACES+=-at DirB=trace@0x25/0x08 # Pin 14 PB3 +#TRACES+=-at DirC=trace@0x10b/0x80 # Pin 42 PL7 +TRACES+=-at EnableA=trace@0x25/0x04 # Pin 16 PB2 +TRACES+=-at EnableB=trace@0x25/0x02 # Pin 15 PB1 +#TRACES+=-at EnableC=trace@0x10b/0x40 # Pin 43 PL6 + +endif + +FIRMWARE=".pio/build/$(DUT)/firmware.elf" + +DIR=$(shell env pwd) + +ifndef SILENCE + SILENCE=0 +endif + +test: .tested + +.tested: result.txt ../judge_pos0.awk + echo DUT=$(DUT) + rm -f .tested + gawk -f ../judge_pos0.awk -v DIR=$(DIR) result.txt + test -f .tested + +result.txt: x.vcd + gawk -v SILENCE=$(SILENCE) -f ../eval.awk x.vcd >/dev/null + +x.vcd: $(SRC) ../run_avr platformio.ini src/Issue250.ino + ~/.platformio/penv/bin/pio run -e $(DUT) || ~/.local/bin/pio run -e $(DUT) || env pio run -e $(DUT) + ../run_avr $(FIRMWARE) -m $(DEVICE) -o x.vcd $(TRACES) + +src/Issue250.ino: + mkdir -p src + cd src; ln -s ../../../../../examples/Issue250/Issue250.ino . + +clean: + rm -fR .pio .tested x.vcd result.txt + diff --git a/extras/tests/simavr_based/test_issue250_30us/expect.txt b/extras/tests/simavr_based/test_issue250_30us/expect.txt new file mode 100644 index 00000000..e69de29b diff --git a/extras/tests/simavr_based/test_issue250_30us/platformio.ini b/extras/tests/simavr_based/test_issue250_30us/platformio.ini new file mode 100644 index 00000000..4136b312 --- /dev/null +++ b/extras/tests/simavr_based/test_issue250_30us/platformio.ini @@ -0,0 +1,32 @@ +; 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 + +[platformio] + +# There should be only one env section for the DUT under test. +# One of +# atmega168p +# atmega328p +# atmega2560_timer1 +# atmega2560_timer3 +# atmega2560_timer4 +# atmega2560_timer5 +# +[common] +# This is the line input to StepperDemo: +#build_flags = -D SIMULATOR -D SIMAVR_TIME_MEASUREMENT -D BLOCK_INTERRUPT_US=30 +build_flags = -D SIMULATOR -D SIMAVR_TIME_MEASUREMENT -D BLOCK_INTERRUPT_US=30 -D LOOPS=100 -D TOGGLE_DIRECTION=false -D USE_MOVETO=false + +[env:atmega328p] +platform = atmelavr +board = nanoatmega328 +framework = arduino +build_flags = -Werror -Wall ${common.build_flags} +lib_extra_dirs = ../../../../.. diff --git a/extras/tests/simavr_based/test_sd_04_timing_2560/expect.txt b/extras/tests/simavr_based/test_sd_04_timing_2560/expect.txt index 03a797e5..9c2057ff 100644 --- a/extras/tests/simavr_based/test_sd_04_timing_2560/expect.txt +++ b/extras/tests/simavr_based/test_sd_04_timing_2560/expect.txt @@ -4,9 +4,9 @@ EnableA: 1*L->H, 1*H->L EnableB: 2*L->H, 1*H->L EnableC: 2*L->H, 1*H->L - StepA: 64000*L->H, 64000*H->L, Max High=28us Total High=521431us - StepB: 64000*L->H, 64000*H->L, Max High=33us Total High=452082us - StepC: 64000*L->H, 64000*H->L, Max High=37us Total High=486045us + StepA: 64000*L->H, 64000*H->L, Max High=25us Total High=311049us + StepB: 64000*L->H, 64000*H->L, Max High=31us Total High=364986us + StepC: 64000*L->H, 64000*H->L, Max High=38us Total High=530547us Position[A]=64000 Position[B]=64000 @@ -15,15 +15,15 @@ Position[C]=64000 Time in EnableA max=233599 us, total=233599 us -Time in EnableB max=246083 us, total=246083 us +Time in EnableB max=246080 us, total=246080 us -Time in EnableC max=254232 us, total=254232 us +Time in EnableC max=254243 us, total=254243 us -Time in FillISR max=2754 us, total=2090247 us +Time in FillISR max=2740 us, total=2116523 us -Time in StepA max=28 us, total=521431 us +Time in StepA max=25 us, total=311049 us -Time in StepB max=33 us, total=452082 us +Time in StepB max=31 us, total=364986 us -Time in StepC max=37 us, total=486045 us +Time in StepC max=38 us, total=530547 us diff --git a/extras/tests/simavr_based/test_sd_04_timing_328p/expect.txt b/extras/tests/simavr_based/test_sd_04_timing_328p/expect.txt index 34bca0eb..f0433a5f 100644 --- a/extras/tests/simavr_based/test_sd_04_timing_328p/expect.txt +++ b/extras/tests/simavr_based/test_sd_04_timing_328p/expect.txt @@ -2,21 +2,21 @@ DirB: 1*L->H, 0*H->L EnableA: 1*L->H, 1*H->L EnableB: 2*L->H, 1*H->L - StepA: 1000*L->H, 1000*H->L, Max High=14us Total High=5599us - StepB: 1000*L->H, 1000*H->L, Max High=19us Total High=5436us + StepA: 1000*L->H, 1000*H->L, Max High=13us Total High=4231us + StepB: 1000*L->H, 1000*H->L, Max High=15us Total High=5045us Position[A]=1000 Position[B]=1000 -Time in EnableA max=225399 us, total=225399 us +Time in EnableA max=225398 us, total=225398 us -Time in EnableB max=238111 us, total=238111 us +Time in EnableB max=238118 us, total=238118 us -Time in FillISR max=2638 us, total=47571 us +Time in FillISR max=2651 us, total=47806 us -Time in StepA max=14 us, total=5599 us +Time in StepA max=13 us, total=4231 us -Time in StepB max=19 us, total=5436 us +Time in StepB max=15 us, total=5045 us -Time in StepISR max=7 us, total=9224 us +Time in StepISR max=6 us, total=8566 us diff --git a/extras/tests/simavr_based/test_sd_04_timing_328p_37k/expect.txt b/extras/tests/simavr_based/test_sd_04_timing_328p_37k/expect.txt index eb1b86d1..e3fcffa0 100644 --- a/extras/tests/simavr_based/test_sd_04_timing_328p_37k/expect.txt +++ b/extras/tests/simavr_based/test_sd_04_timing_328p_37k/expect.txt @@ -2,15 +2,15 @@ DirB: 1*L->H, 0*H->L EnableA: 1*L->H, 1*H->L EnableB: 1*L->H, 0*H->L - StepA: 1000*L->H, 1000*H->L, Max High=11us Total High=5285us + StepA: 1000*L->H, 1000*H->L, Max High=10us Total High=3948us StepB: 0*L->H, 0*H->L, Max High=0us Total High=0us Position[A]=1000 -Time in EnableA max=225400 us, total=225400 us +Time in EnableA max=225399 us, total=225399 us -Time in FillISR max=2015 us, total=27510 us +Time in FillISR max=2023 us, total=27615 us -Time in StepA max=11 us, total=5285 us +Time in StepA max=10 us, total=3948 us -Time in StepISR max=7 us, total=4581 us +Time in StepISR max=5 us, total=3975 us diff --git a/extras/tests/simavr_based/test_sd_11_328p/expect.txt b/extras/tests/simavr_based/test_sd_11_328p/expect.txt index 95fbbeaa..4046871a 100644 --- a/extras/tests/simavr_based/test_sd_11_328p/expect.txt +++ b/extras/tests/simavr_based/test_sd_11_328p/expect.txt @@ -2,11 +2,11 @@ DirB: 1*L->H, 0*H->L EnableA: 1*L->H, 1*H->L EnableB: 1*L->H, 0*H->L - StepA: 99708*L->H, 99708*H->L, Max High=13us Total High=514351us + StepA: 99808*L->H, 99808*H->L, Max High=13us Total High=514436us StepB: 0*L->H, 0*H->L, Max High=0us Total High=0us -Position[A]=50436 +Position[A]=50536 -Time in EnableA max=225396 us, total=225396 us +Time in EnableA max=225395 us, total=225395 us -Time in StepA max=13 us, total=514351 us +Time in StepA max=13 us, total=514436 us diff --git a/extras/tests/simavr_based/test_sd_15_328p/expect.txt b/extras/tests/simavr_based/test_sd_15_328p/expect.txt index 4acdc895..ecfe2309 100644 --- a/extras/tests/simavr_based/test_sd_15_328p/expect.txt +++ b/extras/tests/simavr_based/test_sd_15_328p/expect.txt @@ -2,11 +2,11 @@ DirB: 1*L->H, 0*H->L EnableA: 1*L->H, 1*H->L EnableB: 1*L->H, 0*H->L - StepA: 3434*L->H, 3434*H->L, Max High=12us Total High=17813us + StepA: 3433*L->H, 3433*H->L, Max High=12us Total High=17723us StepB: 0*L->H, 0*H->L, Max High=0us Total High=0us -Position[A]=-1034 +Position[A]=-1033 -Time in EnableA max=225394 us, total=225394 us +Time in EnableA max=225396 us, total=225396 us -Time in StepA max=12 us, total=17813 us +Time in StepA max=12 us, total=17723 us diff --git a/extras/tests/simavr_based/test_sd_16_328p/expect.txt b/extras/tests/simavr_based/test_sd_16_328p/expect.txt index 63fb6cd1..5f130eb4 100644 --- a/extras/tests/simavr_based/test_sd_16_328p/expect.txt +++ b/extras/tests/simavr_based/test_sd_16_328p/expect.txt @@ -2,11 +2,11 @@ DirB: 1*L->H, 0*H->L EnableA: 1*L->H, 1*H->L EnableB: 1*L->H, 0*H->L - StepA: 1122*L->H, 1122*H->L, Max High=11us Total High=5775us + StepA: 1123*L->H, 1123*H->L, Max High=12us Total High=5797us StepB: 0*L->H, 0*H->L, Max High=0us Total High=0us -Position[A]=1122 +Position[A]=1123 -Time in EnableA max=225395 us, total=225395 us +Time in EnableA max=225397 us, total=225397 us -Time in StepA max=11 us, total=5775 us +Time in StepA max=12 us, total=5797 us diff --git a/extras/tests/simavr_based/test_sd_17_328p/expect.txt b/extras/tests/simavr_based/test_sd_17_328p/expect.txt index 7ff79eff..ba5f522e 100644 --- a/extras/tests/simavr_based/test_sd_17_328p/expect.txt +++ b/extras/tests/simavr_based/test_sd_17_328p/expect.txt @@ -2,11 +2,11 @@ DirB: 1*L->H, 0*H->L EnableA: 1*L->H, 1*H->L EnableB: 1*L->H, 0*H->L - StepA: 1431*L->H, 1431*H->L, Max High=12us Total High=7390us + StepA: 1430*L->H, 1430*H->L, Max High=11us Total High=7398us StepB: 0*L->H, 0*H->L, Max High=0us Total High=0us -Position[A]=1431 +Position[A]=1430 -Time in EnableA max=229524 us, total=229524 us +Time in EnableA max=229523 us, total=229523 us -Time in StepA max=12 us, total=7390 us +Time in StepA max=11 us, total=7398 us diff --git a/extras/tests/simavr_based/test_sd_18_328p/expect.txt b/extras/tests/simavr_based/test_sd_18_328p/expect.txt index 9b9f3401..f3b55c91 100644 --- a/extras/tests/simavr_based/test_sd_18_328p/expect.txt +++ b/extras/tests/simavr_based/test_sd_18_328p/expect.txt @@ -2,11 +2,11 @@ DirB: 1*L->H, 0*H->L EnableA: 1*L->H, 1*H->L EnableB: 1*L->H, 0*H->L - StepA: 3866*L->H, 3866*H->L, Max High=12us Total High=19824us + StepA: 3870*L->H, 3870*H->L, Max High=12us Total High=19922us StepB: 0*L->H, 0*H->L, Max High=0us Total High=0us Position[A]=0 Time in EnableA max=229523 us, total=229523 us -Time in StepA max=12 us, total=19824 us +Time in StepA max=12 us, total=19922 us diff --git a/extras/tests/simavr_based/test_sd_18_328p/platformio.ini b/extras/tests/simavr_based/test_sd_18_328p/platformio.ini index f6723879..d940baed 100644 --- a/extras/tests/simavr_based/test_sd_18_328p/platformio.ini +++ b/extras/tests/simavr_based/test_sd_18_328p/platformio.ini @@ -21,7 +21,7 @@ # [common] # This is the line input to StepperDemo: -build_flags = -D SIM_TEST_INPUT='"Q M1 A10 V100 j100000 f w1000 A100000 U X w100 R-1431 W "' +build_flags = -D SIM_TEST_INPUT='"Q M1 A10 V100 j100000 f w1000 A100000 U X w100 R-1433 W "' # The -1431 moves the stepper after the force stop, so that the visible position is 0. # Visible means: counted by watching the external step/direction signals. diff --git a/library.properties b/library.properties index 11dc91bb..0dc0fbb7 100644 --- a/library.properties +++ b/library.properties @@ -1,5 +1,5 @@ name=FastAccelStepper -version=0.30.4 +version=0.30.13 1icense=MIT author=Jochen Kiemes maintainer=Jochen Kiemes diff --git a/src/AVRStepperPins.h b/src/AVRStepperPins.h index 264e0f76..55f2a008 100644 --- a/src/AVRStepperPins.h +++ b/src/AVRStepperPins.h @@ -31,7 +31,7 @@ #endif #define stepPinStepper1A 11 /* OC1A */ #define stepPinStepper1B 12 /* OC1B */ -#define stepPinStepper1C 13 /* OC1B */ +#define stepPinStepper1C 13 /* OC1C */ #define stepPinStepper3A 5 /* OC3A */ #define stepPinStepper3B 2 /* OC3B */ #define stepPinStepper3C 3 /* OC3C */ @@ -41,6 +41,7 @@ #define stepPinStepper5A 46 /* OC5A */ #define stepPinStepper5B 45 /* OC5B */ #define stepPinStepper5C 44 /* OC5C */ + #elif defined(__AVR_ATmega32U4__) #define FAS_TIMER_MODULE 1 #define stepPinStepper1A 9 /* OC1A */ diff --git a/src/FastAccelStepper.cpp b/src/FastAccelStepper.cpp index a36520b8..a995bb9d 100644 --- a/src/FastAccelStepper.cpp +++ b/src/FastAccelStepper.cpp @@ -20,6 +20,7 @@ FastAccelStepper fas_stepper[MAX_STEPPER]; //************************************************************************************************* void FastAccelStepperEngine::init() { _externalCallForPin = NULL; + _stepper_cnt = 0; fas_init_engine(this, 255); for (uint8_t i = 0; i < MAX_STEPPER; i++) { _stepper[i] = NULL; @@ -29,6 +30,7 @@ void FastAccelStepperEngine::init() { #if defined(SUPPORT_CPU_AFFINITY) void FastAccelStepperEngine::init(uint8_t cpu_core) { _externalCallForPin = NULL; + _stepper_cnt = 0; fas_init_engine(this, cpu_core); } #endif @@ -59,8 +61,12 @@ bool FastAccelStepperEngine::isDirPinBusy(uint8_t dir_pin, } //************************************************************************************************* #if !defined(SUPPORT_SELECT_DRIVER_TYPE) +FastAccelStepper* FastAccelStepperEngine::stepperConnectToPin(uint8_t step_pin) +#else FastAccelStepper* FastAccelStepperEngine::stepperConnectToPin( - uint8_t step_pin) { + uint8_t step_pin, uint8_t driver_type) +#endif +{ // Check if already connected for (uint8_t i = 0; i < MAX_STEPPER; i++) { FastAccelStepper* s = _stepper[i]; @@ -73,6 +79,7 @@ FastAccelStepper* FastAccelStepperEngine::stepperConnectToPin( if (!_isValidStepPin(step_pin)) { return NULL; } +#if !defined(SUPPORT_SELECT_DRIVER_TYPE) int8_t fas_stepper_num = StepperQueue::queueNumForStepPin(step_pin); if (fas_stepper_num < 0) { // flexible, so just choose next if (_stepper_cnt >= MAX_STEPPER) { @@ -80,37 +87,7 @@ FastAccelStepper* FastAccelStepperEngine::stepperConnectToPin( } fas_stepper_num = _stepper_cnt; } - _stepper_cnt++; - - FastAccelStepper* s = &fas_stepper[fas_stepper_num]; - _stepper[fas_stepper_num] = s; - s->init(this, fas_stepper_num, step_pin); - for (uint8_t i = 0; i < _stepper_cnt; i++) { - FastAccelStepper* sx = _stepper[i]; - fas_queue[sx->_queue_num].adjustSpeedToStepperCount(_stepper_cnt); - } - return s; -} #else -FastAccelStepper* FastAccelStepperEngine::stepperConnectToPin( - uint8_t step_pin) { - return stepperConnectToPin(step_pin, DRIVER_DONT_CARE); -} - -FastAccelStepper* FastAccelStepperEngine::stepperConnectToPin( - uint8_t step_pin, uint8_t driver_type) { - // Check if already connected - for (uint8_t i = 0; i < MAX_STEPPER; i++) { - FastAccelStepper* s = _stepper[i]; - if (s) { - if (s->getStepPin() == step_pin) { - return NULL; - } - } - } - if (!_isValidStepPin(step_pin)) { - return NULL; - } uint8_t queue_from = 0; uint8_t queue_to = QUEUES_MCPWM_PCNT + QUEUES_RMT; if (driver_type == DRIVER_MCPWM_PCNT) { @@ -129,6 +106,7 @@ FastAccelStepper* FastAccelStepperEngine::stepperConnectToPin( if (fas_stepper_num < 0) { return NULL; } +#endif _stepper_cnt++; FastAccelStepper* s = &fas_stepper[fas_stepper_num]; @@ -142,7 +120,6 @@ FastAccelStepper* FastAccelStepperEngine::stepperConnectToPin( } return s; } -#endif //************************************************************************************************* void FastAccelStepperEngine::setDebugLed(uint8_t ledPin) { fas_ledPin = ledPin; @@ -400,12 +377,14 @@ void FastAccelStepper::fill_queue() { // preconditions are fulfilled, so create the command(s) NextCommand cmd; - // Plan ahead for max. 20 ms. Currently hard coded + // Plan ahead for max. 20 ms and minimum two commands. + // This is now configurable using _forward_planning_in_ticks. bool delayed_start = !q->isRunning(); bool need_delayed_start = false; uint32_t ticksPrepared = q->ticksInQueue(); while (!isQueueFull() && - ((ticksPrepared < TICKS_PER_S / 50) || q->queueEntries() <= 1) && + ((ticksPrepared < _forward_planning_in_ticks) || + q->queueEntries() <= 1) && _rg.isRampGeneratorActive()) { #if (TEST_MEASURE_ISR_SINGLE_FILL == 1) // For run time measurement @@ -529,6 +508,9 @@ void FastAccelStepper::init(FastAccelStepperEngine* engine, uint8_t num, _stepPin = step_pin; _dirHighCountsUp = true; _dirPin = PIN_UNDEFINED; + _enablePinHighActive = PIN_UNDEFINED; + _enablePinLowActive = PIN_UNDEFINED; + _forward_planning_in_ticks = TICKS_PER_S / 50; _rg.init(); _queue_num = num; @@ -771,34 +753,38 @@ uint32_t FastAccelStepper::getPeriodInUsAfterCommandsCompleted() { } return 0; } -int32_t FastAccelStepper::getCurrentSpeedInUs() { - uint32_t ticks = fas_queue[_queue_num].getActualTicks(); - if (ticks == 0) { - ticks = getPeriodInTicksAfterCommandsCompleted(); +void FastAccelStepper::getCurrentSpeedInTicks(struct actual_ticks_s* speed, + bool realtime) { + bool valid; + if (realtime) { + valid = fas_queue[_queue_num].getActualTicksWithDirection(speed); + } else { + valid = false; } - int32_t speed_in_us = ticks / (TICKS_PER_S / 1000000); - switch (_rg.rampState() & RAMP_DIRECTION_MASK) { - case RAMP_DIRECTION_COUNT_UP: - return speed_in_us; - case RAMP_DIRECTION_COUNT_DOWN: - return -speed_in_us; + if (!valid) { + if (_rg.isRampGeneratorActive()) { + _rg.getCurrentSpeedInTicks(speed); + } } - return 0; } -int32_t FastAccelStepper::getCurrentSpeedInMilliHz() { - uint32_t ticks = fas_queue[_queue_num].getActualTicks(); - if (ticks == 0) { - ticks = getPeriodInTicksAfterCommandsCompleted(); - } - int32_t speed_in_milli_hz = 0; - if (ticks > 0) { - speed_in_milli_hz = ((uint32_t)250 * TICKS_PER_S) / ticks * 4; +int32_t FastAccelStepper::getCurrentSpeedInUs(bool realtime) { + struct actual_ticks_s speed; + getCurrentSpeedInTicks(&speed, realtime); + int32_t speed_in_us = speed.ticks / (TICKS_PER_S / 1000000); + if (speed.count_up) { + return speed_in_us; } - switch (_rg.rampState() & RAMP_DIRECTION_MASK) { - case RAMP_DIRECTION_COUNT_UP: - return speed_in_milli_hz; - case RAMP_DIRECTION_COUNT_DOWN: - return -speed_in_milli_hz; + return -speed_in_us; +} +int32_t FastAccelStepper::getCurrentSpeedInMilliHz(bool realtime) { + struct actual_ticks_s speed; + getCurrentSpeedInTicks(&speed, realtime); + if (speed.ticks > 0) { + int32_t speed_in_mhz = ((uint32_t)250 * TICKS_PER_S) / speed.ticks * 4; + if (speed.count_up) { + return speed_in_mhz; + } + return -speed_in_mhz; } return 0; } @@ -820,6 +806,11 @@ uint32_t FastAccelStepper::getMaxSpeedInMilliHz() { uint32_t speed_in_milli_hz = ((uint32_t)250 * TICKS_PER_S) / ticks * 4; return speed_in_milli_hz; } +#if SUPPORT_UNSAFE_ABS_SPEED_LIMIT_SETTING == 1 +void FastAccelStepper::setAbsoluteSpeedLimit(uint16_t max_speed_in_ticks) { + fas_queue[_queue_num].setAbsoluteSpeedLimit(max_speed_in_ticks); +} +#endif int8_t FastAccelStepper::setSpeedInTicks(uint32_t min_step_ticks) { if (min_step_ticks < getMaxSpeedInTicks()) { return -1; diff --git a/src/FastAccelStepper.h b/src/FastAccelStepper.h index 3997ed16..35637c12 100644 --- a/src/FastAccelStepper.h +++ b/src/FastAccelStepper.h @@ -2,7 +2,7 @@ #define FASTACCELSTEPPER_H #include #include "PoorManFloat.h" -#include "common.h" +#include "fas_common.h" // # FastAccelStepper // @@ -81,8 +81,9 @@ class FastAccelStepperEngine { // hardware may have limitations - e.g. no stepper resources anymore, or the // step pin cannot be used, then NULL is returned. So it is advised to check // the return value of this call. +#if !defined(SUPPORT_SELECT_DRIVER_TYPE) FastAccelStepper* stepperConnectToPin(uint8_t step_pin); - +#endif // For e.g. esp32, there are two types of driver. // One using mcpwm and pcnt module. And another using rmt module. // This call allows to select the respective driver @@ -90,7 +91,8 @@ class FastAccelStepperEngine { #define DRIVER_MCPWM_PCNT 0 #define DRIVER_RMT 1 #define DRIVER_DONT_CARE 2 - FastAccelStepper* stepperConnectToPin(uint8_t step_pin, uint8_t driver_type); + FastAccelStepper* stepperConnectToPin(uint8_t step_pin, + uint8_t driver_type = DRIVER_DONT_CARE); #endif // Comments to valid pins: @@ -187,8 +189,8 @@ class FastAccelStepperEngine { #define RAMP_DIRECTION_COUNT_DOWN 64 // A ramp state value of 2 is set after any move call on a stopped motor -// and until the stepper task. The stepper task will then control the direction -// flags +// and until the stepper task is serviced. The stepper task will then +// control the direction flags #include "RampGenerator.h" @@ -331,6 +333,14 @@ class FastAccelStepper { uint32_t getMaxSpeedInHz(); uint32_t getMaxSpeedInMilliHz(); + // For esp32 and avr, the device's maximum allowed speed can be overridden. + // Allocating a new stepper will override any absolute speed limit. + // This is absolutely untested, no error checking implemented. + // Use at your own risk ! +#if SUPPORT_UNSAFE_ABS_SPEED_LIMIT_SETTING == 1 + void setAbsoluteSpeedLimit(uint16_t max_speed_in_ticks); +#endif + // Setting the speed can be done with the four `setSpeed...()` calls. // The new value will be used only after call of these functions: // @@ -365,8 +375,21 @@ class FastAccelStepper { // | > 0 | while position counting up  | // | < 0 | while position counting down | // - int32_t getCurrentSpeedInUs(); - int32_t getCurrentSpeedInMilliHz(); + // If the parameter realtime is true, then the most actual speed + // from the stepper queue is derived. This works only, if the queue + // does not contain pauses, which is normally the case for slow speeds. + // Otherwise the speed from the ramp generator is reported, which is + // done always in case of `realtime == false`. That speed is typically + // the value of the speed a couple of milliseconds later. + // + // The drawback of `realtime == true` is, that the reported speed + // may either come from the queue or from the ramp generator. + // This means the returned speed may have jumps during + // acceleration/deceleration. + // + // For backward compatibility, the default is true. + int32_t getCurrentSpeedInUs(bool realtime = true); + int32_t getCurrentSpeedInMilliHz(bool realtime = true); // ## Acceleration // setAcceleration() expects as parameter the change of speed @@ -512,6 +535,38 @@ class FastAccelStepper { // In keep running mode, the targetPos() is not updated inline int32_t targetPos() { return _rg.targetPosition(); } + // The stepper task adds commands to the stepper queue until + // either at least two commands are planned, or the commands + // cover sufficient time into the future. Default value for that time is 20ms. + // + // The stepper task is cyclically executed every ~4ms. + // Especially for avr, the step interrupts puts a significant load on the uC, + // so the cyclical stepper task can even run for 2-3 ms. On top of that, + // other interrupts caused by the application could increase the load even + // further. + // + // Consequently, the forward planning should fill the queue for ideally two + // cycles, this means 8ms. This means, the default 20ms provide a sufficient + // margin and even a missed cycle is not an issue. + // + // The drawback of the 20ms is, that any change in speed/acceleration are + // added after those 20ms and for an application, requiring fast reaction + // times, this may impact the expected performance. + // + // Due to this the forward planning time can be adjusted with the following + // API call for each stepper individually. + // + // Attention: + // - This is only for advanced users: no error checking is implemented. + // - Only change the forward planning time, if the stepper is not running. + // - Too small values bear the risk of a stepper running at full speed + // suddenly stopping + // due to lack of commands in the queue. + inline void setForwardPlanningTimeInMs(uint8_t ms) { + _forward_planning_in_ticks = ms; + _forward_planning_in_ticks *= TICKS_PER_S / 1000; // ticks per ms + } + // ## Low Level Stepper Queue Management (low level access) // // If the queue is already running, then the start parameter is obsolote. @@ -646,6 +701,7 @@ class FastAccelStepper { bool needAutoDisable(); bool agreeWithAutoDisable(); bool usesAutoEnablePin(uint8_t pin); + void getCurrentSpeedInTicks(struct actual_ticks_s* speed, bool realtime); FastAccelStepperEngine* _engine; RampGenerator _rg; @@ -662,6 +718,8 @@ class FastAccelStepper { uint16_t _off_delay_count; uint16_t _auto_disable_delay_counter; + uint32_t _forward_planning_in_ticks; + #if defined(SUPPORT_ESP32_PULSE_COUNTER) int16_t _attached_pulse_cnt_unit; #endif diff --git a/src/RampCalculator.h b/src/RampCalculator.h index efa4862f..8527605e 100644 --- a/src/RampCalculator.h +++ b/src/RampCalculator.h @@ -4,7 +4,7 @@ #include #include "PoorManFloat.h" -#include "common.h" +#include "fas_common.h" #if (TICKS_PER_S == 16000000L) #define PMF_TICKS_PER_S PMF_CONST_16E6 diff --git a/src/RampConstAcceleration.cpp b/src/RampConstAcceleration.cpp index fdeb0ad9..2a230b7d 100644 --- a/src/RampConstAcceleration.cpp +++ b/src/RampConstAcceleration.cpp @@ -4,7 +4,7 @@ #include "StepperISR.h" #include "RampConstAcceleration.h" -#include "common.h" +#include "fas_common.h" #ifdef SUPPORT_PMF_TIMER_FREQ_VARIABLES static pmf_logarithmic pmfl_timer_freq; diff --git a/src/RampConstAcceleration.h b/src/RampConstAcceleration.h index 65130c0d..50b9bc16 100644 --- a/src/RampConstAcceleration.h +++ b/src/RampConstAcceleration.h @@ -1,7 +1,7 @@ #ifndef RAMP_CONST_ACCELERATION_H #define RAMP_CONST_ACCELERATION_H -#include "common.h" +#include "fas_common.h" struct ramp_ro_s { struct ramp_config_s config; diff --git a/src/RampGenerator.h b/src/RampGenerator.h index 02a6b309..8c7c8766 100644 --- a/src/RampGenerator.h +++ b/src/RampGenerator.h @@ -4,7 +4,7 @@ #include "FastAccelStepper.h" #include "RampCalculator.h" #include "RampConstAcceleration.h" -#include "common.h" +#include "fas_common.h" class FastAccelStepper; @@ -89,6 +89,13 @@ class RampGenerator { void getNextCommand(const struct queue_end_s *queue_end, NextCommand *cmd_out); void afterCommandEnqueued(NextCommand *cmd_in); + void getCurrentSpeedInTicks(struct actual_ticks_s *speed) { + fasDisableInterrupts(); + speed->ticks = _rw.curr_ticks; + uint8_t rs = _rw.rampState(); + fasEnableInterrupts(); + speed->count_up = ((rs & RAMP_DIRECTION_COUNT_UP) != 0); + } uint32_t getCurrentPeriodInTicks() { fasDisableInterrupts(); uint32_t ticks = _rw.curr_ticks; diff --git a/src/StepperISR.cpp b/src/StepperISR.cpp index dfd7f356..dddcde9d 100644 --- a/src/StepperISR.cpp +++ b/src/StepperISR.cpp @@ -281,28 +281,32 @@ bool StepperQueue::hasTicksInQueue(uint32_t min_ticks) { return false; } -uint16_t StepperQueue::getActualTicks() { - // Retrieve current step rate from the current view. - // This is valid only, if the command describes more than one step +bool StepperQueue::getActualTicksWithDirection(struct actual_ticks_s* speed) { + // Retrieve current step rate from the current command. + // This is valid only, if the command describes more than one step, + // or if the next command contains one step, too. fasDisableInterrupts(); uint8_t rp = read_idx; uint8_t wp = next_write_idx; fasEnableInterrupts(); if (wp == rp) { - return 0; + speed->ticks = 0; + return true; } struct queue_entry* e = &entry[rp & QUEUE_LEN_MASK]; if (e->hasSteps) { + speed->count_up = e->countUp; + speed->ticks = e->ticks; if (e->moreThanOneStep) { - return e->ticks; + return true; } if (wp != ++rp) { if (entry[rp & QUEUE_LEN_MASK].hasSteps) { - return e->ticks; + return true; } } } - return 0; + return false; } void StepperQueue::_initVars() { @@ -322,7 +326,7 @@ void StepperQueue::_initVars() { dirHighCountsUp = true; #if defined(ARDUINO_ARCH_AVR) _isRunning = false; - _prepareForStop = false; + _noMoreCommands = false; #endif #if defined(SUPPORT_ESP32) _isRunning = false; diff --git a/src/StepperISR.h b/src/StepperISR.h index a00e61e3..481a390d 100644 --- a/src/StepperISR.h +++ b/src/StepperISR.h @@ -1,7 +1,7 @@ #include #include "FastAccelStepper.h" -#include "common.h" +#include "fas_common.h" // Here are the global variables to interface with the interrupts @@ -80,13 +80,15 @@ class StepperQueue { bool bufferContainsSteps[2]; #endif #if defined(SUPPORT_DIR_PIN_MASK) - // avr uses uint8_t and sam needs uint32_t - // so make the SUPPORT_DIR_PIN_MASK dual use volatile SUPPORT_DIR_PIN_MASK* _dirPinPort; SUPPORT_DIR_PIN_MASK _dirPinMask; #endif +#if defined(SUPPORT_DIR_TOGGLE_PIN_MASK) + volatile SUPPORT_DIR_TOGGLE_PIN_MASK* _dirTogglePinPort; + SUPPORT_DIR_TOGGLE_PIN_MASK _dirTogglePinMask; +#endif #if defined(SUPPORT_AVR) - volatile bool _prepareForStop; + volatile bool _noMoreCommands; volatile bool _isRunning; inline bool isRunning() { return _isRunning; } inline bool isReadyForCommands() { return true; } @@ -139,7 +141,7 @@ class StepperQueue { int32_t getCurrentPosition(); uint32_t ticksInQueue(); bool hasTicksInQueue(uint32_t min_ticks); - uint16_t getActualTicks(); + bool getActualTicksWithDirection(struct actual_ticks_s* speed); volatile uint16_t getMaxSpeedInTicks() { return max_speed_in_ticks; } @@ -177,8 +179,17 @@ class StepperQueue { _dirPinPort = portOutputRegister(digitalPinToPort(dir_pin)); _dirPinMask = digitalPinToBitMask(dir_pin); } +#endif +#if defined(SUPPORT_DIR_TOGGLE_PIN_MASK) + if ((dir_pin != PIN_UNDEFINED) && ((dir_pin & PIN_EXTERNAL_FLAG) == 0)) { + _dirTogglePinPort = portInputRegister(digitalPinToPort(dir_pin)); + _dirTogglePinMask = digitalPinToBitMask(dir_pin); + } #endif } +#if SUPPORT_UNSAFE_ABS_SPEED_LIMIT_SETTING == 1 + void setAbsoluteSpeedLimit(uint16_t ticks) { max_speed_in_ticks = ticks; } +#endif void adjustSpeedToStepperCount(uint8_t steppers); static bool isValidStepPin(uint8_t step_pin); static int8_t queueNumForStepPin(uint8_t step_pin); diff --git a/src/StepperISR_avr.cpp b/src/StepperISR_avr.cpp index 7590778d..2b1b7a16 100644 --- a/src/StepperISR_avr.cpp +++ b/src/StepperISR_avr.cpp @@ -12,11 +12,15 @@ // Toggle is 0 1 // Disconnect is 0 0 // -#define Stepper_OneToZero(T, X) TCCR##T##A = TCCR##T##A & ~_BV(COM##T##X##0) #define Stepper_Zero(T, X) \ TCCR##T##A = (TCCR##T##A | _BV(COM##T##X##1)) & ~_BV(COM##T##X##0) +// Force compare of Stepper_Toggle appears to be broken in simavr +// In other words, use of Stepper_Toggle yields errors in simavr, for which root +// cause is unclear +#ifdef DISABLE #define Stepper_Toggle(T, X) \ TCCR##T##A = (TCCR##T##A | _BV(COM##T##X##0)) & ~_BV(COM##T##X##1) +#endif #define Stepper_One(T, X) TCCR##T##A |= _BV(COM##T##X##1) | _BV(COM##T##X##0) #define Stepper_Disconnect(T, X) \ TCCR##T##A &= ~(_BV(COM##T##X##1) | _BV(COM##T##X##0)) @@ -26,6 +30,12 @@ #define Stepper_IsDisconnected(T, X) \ ((TCCR##T##A & (_BV(COM##T##X##0) | _BV(COM##T##X##1))) == 0) #define Stepper_IsOneIfOutput(T, X) ((TCCR##T##A & _BV(COM##T##X##0)) != 0) +#define Stepper_ToggleDirection(CHANNEL) \ + *fas_queue_##CHANNEL._dirTogglePinPort = fas_queue_##CHANNEL._dirTogglePinMask +#define PREPARE_DIRECTION_PIN(CHANNEL) \ + if (e->toggle_dir) { \ + Stepper_ToggleDirection(CHANNEL); \ + } #ifdef SIMAVR_TIME_MEASUREMENT #define prepareISRtimeMeasurement() DDRB |= 0x18 @@ -65,6 +75,7 @@ #define EnableCompareInterrupt(T, X) TIMSK##T |= _BV(OCIE##T##X) #define ClearInterruptFlag(T, X) TIFR##T = _BV(OCF##T##X) #define SetTimerCompareRelative(T, X, D) OCR##T##X = TCNT##T + D +#define InterruptFlagIsSet(T, X) ((TIFR##T & _BV(OCF##T##X)) != 0) #define ConfigureTimer(T) \ { \ @@ -126,74 +137,65 @@ void StepperQueue::init(uint8_t queue_num, uint8_t step_pin) { // Remark: Interrupt Flag is automatically cleared on ISR execution // // If reaching here without further commands, then the queue is done -#define AVR_STEPPER_ISR(T, CHANNEL) \ - ISR(TIMER##T##_COMP##CHANNEL##_vect) { \ - enterStepperISR(); \ - uint8_t rp = fas_queue_##CHANNEL.read_idx; \ - if (rp == fas_queue_##CHANNEL.next_write_idx) { \ - /* queue is empty => set to disconnect */ \ - Stepper_Disconnect(T, CHANNEL); \ - /* force compare to ensure disconnect */ \ - ForceCompare(T, CHANNEL); \ - /* disable compare interrupt */ \ - DisableCompareInterrupt(T, CHANNEL); \ - fas_queue_##CHANNEL._isRunning = false; \ - fas_queue_##CHANNEL._prepareForStop = false; \ - exitStepperISR(); \ - return; \ - } \ - struct queue_entry* e = &fas_queue_##CHANNEL.entry[rp & QUEUE_LEN_MASK]; \ - /* There is a risk, that this new compare time is delayed by one cycle */ \ - OCR##T##CHANNEL += e->ticks; \ - if (Stepper_IsOneIfOutput(T, CHANNEL)) { \ - /* Clear output bit by another compare event */ \ - Stepper_OneToZero(T, CHANNEL); \ - ForceCompare(T, CHANNEL); \ - if (e->steps-- > 1) { \ - /* perform another step with this queue entry */ \ - Stepper_One(T, CHANNEL); \ - exitStepperISR(); \ - return; \ - } \ - } else if (fas_queue_##CHANNEL._prepareForStop) { \ - /* new command received after running out of commands */ \ - /* if this new command requires a step, then this step would be lost \ - */ \ - fas_queue_##CHANNEL._prepareForStop = false; \ - if (e->steps > 0) { \ - /* That's the problem, so generate a step */ \ - Stepper_One(T, CHANNEL); \ - ForceCompare(T, CHANNEL); \ - /* Use a high time of 3us */ \ - delayMicroseconds(3); \ - /* Clear output bit by another toggle */ \ - Stepper_OneToZero(T, CHANNEL); \ - ForceCompare(T, CHANNEL); \ - if (e->steps-- > 1) { \ - /* perform another step with this queue entry */ \ - Stepper_One(T, CHANNEL); \ - exitStepperISR(); \ - return; \ - } \ - } \ - } \ - if (TEST_NOT_REPEATING_ENTRY) { \ - rp++; \ - } \ - fas_queue_##CHANNEL.read_idx = rp; \ - if (rp != fas_queue_##CHANNEL.next_write_idx) { \ - /* command in queue */ \ - e = &fas_queue_##CHANNEL.entry[rp & QUEUE_LEN_MASK]; \ - if (e->steps != 0) { \ - Stepper_One(T, CHANNEL); \ - } \ - if (e->toggle_dir) { \ - *fas_queue_##CHANNEL._dirPinPort ^= fas_queue_##CHANNEL._dirPinMask; \ - } \ - } else { \ - fas_queue_##CHANNEL._prepareForStop = true; \ - } \ - exitStepperISR(); \ +#define AVR_STEPPER_ISR(T, CHANNEL) \ + ISR(TIMER##T##_COMP##CHANNEL##_vect) { \ + enterStepperISR(); \ + uint8_t rp = fas_queue_##CHANNEL.read_idx; \ + uint8_t wp = fas_queue_##CHANNEL.next_write_idx; \ + if (rp == wp) { \ + /* queue is empty => set to disconnect */ \ + /* disable compare interrupt */ \ + DisableCompareInterrupt(T, CHANNEL); \ + Stepper_Disconnect(T, CHANNEL); \ + /* force compare to ensure disconnect */ \ + ForceCompare(T, CHANNEL); \ + fas_queue_##CHANNEL._isRunning = false; \ + fas_queue_##CHANNEL._noMoreCommands = false; \ + exitStepperISR(); \ + return; \ + } \ + struct queue_entry* e = &fas_queue_##CHANNEL.entry[rp & QUEUE_LEN_MASK]; \ + /* There is a risk, that this new compare time is delayed by one cycle */ \ + uint16_t ticks = e->ticks; \ + /* Set output to zero, this works in any case. In case of pause: no-op */ \ + Stepper_Zero(T, CHANNEL); \ + ForceCompare(T, CHANNEL); \ + if (e->steps > 1) { \ + /* perform another step with this queue entry */ \ + e->steps--; \ + Stepper_One(T, CHANNEL); \ + } else { \ + /* either pause command or no more steps */ \ + if (fas_queue_##CHANNEL._noMoreCommands) { \ + /* new command received after running out of commands */ \ + /* if this new command requires a step, then this step would be lost \ + */ \ + fas_queue_##CHANNEL._noMoreCommands = false; \ + if (e->steps != 0) { \ + /* New command needs steps, so do it immediately */ \ + ticks = 10; \ + } \ + } else if (TEST_NOT_REPEATING_ENTRY) { \ + rp++; \ + fas_queue_##CHANNEL.read_idx = rp; \ + if (rp == wp) { \ + /* queue is empty, wait this command to complete, then disconnect */ \ + fas_queue_##CHANNEL._noMoreCommands = true; \ + OCR##T##CHANNEL += ticks; \ + exitStepperISR(); \ + return; \ + } \ + e = &fas_queue_##CHANNEL.entry[rp & QUEUE_LEN_MASK]; \ + } \ + if (e->toggle_dir) { \ + Stepper_ToggleDirection(CHANNEL); \ + } \ + if (e->steps != 0) { \ + Stepper_One(T, CHANNEL); \ + } \ + } \ + OCR##T##CHANNEL += ticks; \ + exitStepperISR(); \ } #define AVR_STEPPER_ISR_GEN(T, CHANNEL) AVR_STEPPER_ISR(T, CHANNEL) @@ -232,18 +234,11 @@ AVR_CYCLIC_ISR_GEN(FAS_TIMER_MODULE) rp = fas_queue_##CHANNEL.read_idx; \ e = &fas_queue_##CHANNEL.entry[rp & QUEUE_LEN_MASK]; -#define PREPARE_DIRECTION_PIN(CHANNEL) \ - if (e->toggle_dir) { \ - *fas_queue_##CHANNEL._dirPinPort ^= fas_queue_##CHANNEL._dirPinMask; \ - } - #define AVR_START_QUEUE(T, CHANNEL) \ - _isRunning = true; \ - _prepareForStop = false; \ /* ensure no compare event */ \ SetTimerCompareRelative(T, CHANNEL, 32768); \ /* set output one, if steps to be generated */ \ - if (e->steps > 0) { \ + if (e->steps != 0) { \ Stepper_One(T, CHANNEL); \ } else { \ Stepper_Zero(T, CHANNEL); \ @@ -253,12 +248,15 @@ AVR_CYCLIC_ISR_GEN(FAS_TIMER_MODULE) /* enable compare interrupt */ \ EnableCompareInterrupt(T, CHANNEL); \ /* start */ \ - SetTimerCompareRelative(T, CHANNEL, 10); + noInterrupts(); \ + SetTimerCompareRelative(T, CHANNEL, 10); \ + interrupts(); void StepperQueue::startQueue() { uint8_t rp; struct queue_entry* e; + _isRunning = true; switch (channel) { case channelA: GET_ENTRY_PTR(FAS_TIMER_MODULE, A) @@ -340,18 +338,11 @@ int8_t StepperQueue::queueNumForStepPin(uint8_t step_pin) { return -1; } void StepperQueue::adjustSpeedToStepperCount(uint8_t steppers) { - // using test_sd_04_timing_2560 version 0.25.6 as reference - // manageStepper (fillISR) already needs max 3ms ! - // so 25kHz for three steppers is on the limit - // // commit 9577e9bfd4b9a6cf1ad830901c00c8b129a62aee fails // test_sd_04_timing_2560 as timer 3 reaches 40us. // This includes port set/clear for timer measurement. // So choose 20kHz // - // using test_sd_04_timing_328p version 0.25.6 as reference - // manageStepper (fillISR) already needs max 2.3 ms ! - // // check if Issue_152.ino, the interrupt need 14us. // So 70000 Steps/s is too high. if (steppers == 1) { diff --git a/src/StepperISR_esp32_mcpwm_pcnt.cpp b/src/StepperISR_esp32_mcpwm_pcnt.cpp index 4177ede7..e0910e50 100644 --- a/src/StepperISR_esp32_mcpwm_pcnt.cpp +++ b/src/StepperISR_esp32_mcpwm_pcnt.cpp @@ -55,7 +55,6 @@ static struct mapping_s channel2mapping[NUM_QUEUES] = { cmpr_tea_int_ena : MCPWM_OP2_TEA_INT_ENA, cmpr_tea_int_raw : MCPWM_OP2_TEA_INT_RAW }, -#ifndef SUPPORT_ESP32S3_MCPWM_PCNT { mcpwm_unit : MCPWM_UNIT_1, timer : 0, @@ -66,6 +65,7 @@ static struct mapping_s channel2mapping[NUM_QUEUES] = { cmpr_tea_int_ena : MCPWM_OP0_TEA_INT_ENA, cmpr_tea_int_raw : MCPWM_OP0_TEA_INT_RAW }, +#ifndef SUPPORT_ESP32S3_MCPWM_PCNT { mcpwm_unit : MCPWM_UNIT_1, timer : 1, @@ -339,8 +339,8 @@ static void IRAM_ATTR mcpwm0_isr_service(void *arg) { MCPWM_SERVICE(MCPWM0, 2, 2); } static void IRAM_ATTR mcpwm1_isr_service(void *arg) { -#ifndef SUPPORT_ESP32S3_MCPWM_PCNT MCPWM_SERVICE(MCPWM1, 0, 3); +#ifndef SUPPORT_ESP32S3_MCPWM_PCNT MCPWM_SERVICE(MCPWM1, 1, 4); MCPWM_SERVICE(MCPWM1, 2, 5); #endif diff --git a/src/StepperISR_esp32_rmt.cpp b/src/StepperISR_esp32_rmt.cpp index 113c7704..e2b4ca59 100644 --- a/src/StepperISR_esp32_rmt.cpp +++ b/src/StepperISR_esp32_rmt.cpp @@ -1,7 +1,8 @@ #include "StepperISR.h" -#ifdef SUPPORT_ESP32_RMT +#if defined(SUPPORT_ESP32_RMT) && !defined(SUPPORT_ESP32C3_RMT) && \ + !defined(SUPPORT_ESP32S3_RMT) -//#define TEST_MODE +// #define TEST_MODE #include "test_probe.h" @@ -115,10 +116,10 @@ static void IRAM_ATTR apply_command(StepperQueue *q, bool fill_part_one, if (steps < PART_SIZE / 2) { for (uint8_t i = 1; i < steps; i++) { // steps-1 iterations - *data++ = 0x40017fff | 0x8000; + *data++ = 0x40007fff | 0x8000; *data++ = 0x20002000; } - *data++ = 0x40017fff | 0x8000; + *data++ = 0x40007fff | 0x8000; uint16_t delta = PART_SIZE - 2 * steps; delta <<= 5; *data++ = 0x20002000 - delta; @@ -132,10 +133,10 @@ static void IRAM_ATTR apply_command(StepperQueue *q, bool fill_part_one, } else { steps -= PART_SIZE / 2; for (uint8_t i = 0; i < PART_SIZE / 2 - 1; i++) { - *data++ = 0x40017fff | 0x8000; + *data++ = 0x40007fff | 0x8000; *data++ = 0x20002000; } - *data++ = 0x40017fff | 0x8000; + *data++ = 0x40007fff | 0x8000; last_entry = 0x20002000; } } else if ((steps < 2 * PART_SIZE) && (steps != PART_SIZE)) { @@ -385,7 +386,7 @@ void StepperQueue::disconnect_rmt() { } void StepperQueue::startQueue_rmt() { -//#define TRACE +// #define TRACE #ifdef TRACE Serial.println("START"); #endif @@ -406,7 +407,7 @@ void StepperQueue::startQueue_rmt() { #endif rmt_tx_stop(channel); // rmt_rx_stop(channel); - rmt_memory_rw_rst(channel); + // rmt_tx_memory_reset(channel); // the following assignment should not be needed; // RMT.data_ch[channel] = 0; uint32_t *mem = FAS_RMT_MEM(channel); @@ -424,7 +425,7 @@ void StepperQueue::startQueue_rmt() { rmt_set_tx_thr_intr_en(channel, false, 0); // RMT.apb_conf.mem_tx_wrap_en = 0; -//#define TRACE +// #define TRACE #ifdef TRACE Serial.print("Queue:"); Serial.print(read_idx); diff --git a/src/StepperISR_esp32c3_rmt.cpp b/src/StepperISR_esp32c3_rmt.cpp new file mode 100644 index 00000000..dea0d67a --- /dev/null +++ b/src/StepperISR_esp32c3_rmt.cpp @@ -0,0 +1,653 @@ +#include "StepperISR.h" +#ifdef SUPPORT_ESP32C3_RMT + +//#define TEST_MODE +//#define TRACE + +#include "test_probe.h" + +// The following concept is in use: +// +// The rmt buffer is split into two parts. +// Each part will hold one command (or part of). +// After the two parts an end marker is placed. +// +// Of these 32 bits, the low 16-bit entry is sent first and the high entry +// second. +// Every 16 bit entry defines with MSB the output level and the lower 15 bits +// the ticks. +// +// Important difference of esp32c3 (compared to esp32): +// - configuration updates need an conf_update strobe +// (apparently the manual is not correct by mentioning to set conf_update +// first) +// - if the end marker is hit in continuous mode, there is no end interrupt +// - there is no tick lost with the end marker +// - minimum periods as per relation 1 and 2 to be adhered to +// +// +#ifdef SUPPORT_ESP32C3_RMT +#define PART_SIZE 23 +#define RMT_MEM_SIZE 48 +#else +#error +#define PART_SIZE 31 +#define RMT_MEM_SIZE 64 +#endif + +// In order to avoid threshold/end interrupt on end, add one +#define enable_rmt_interrupts(channel) \ + { \ + RMT.tx_lim[channel].RMT_LIMIT = PART_SIZE + 2; \ + RMT.tx_conf[channel].conf_update = 1; \ + RMT.tx_conf[channel].conf_update = 0; \ + RMT.int_clr.val |= 0x101 << channel; \ + RMT.int_ena.val |= 0x101 << channel; \ + } +#define disable_rmt_interrupts(channel) \ + { RMT.int_ena.val &= ~(0x101 << channel); } + +void IRAM_ATTR StepperQueue::stop_rmt(bool both) { + // We are stopping the rmt by letting it run into the end at high speed. + // + // disable the interrupts + // rmt_set_tx_intr_en(channel, false); + // rmt_set_tx_thr_intr_en(channel, false, 0); + + // stop esp32 rmt, by let it hit the end + RMT.tx_conf[channel].tx_conti_mode = 0; + RMT.tx_conf[channel].conf_update = 1; + RMT.tx_conf[channel].conf_update = 0; + + // replace second part of buffer with pauses + uint32_t *data = FAS_RMT_MEM(channel); + uint8_t start = both ? 0 : PART_SIZE; + data = &data[start]; + for (uint8_t i = start; i < 2 * PART_SIZE; i++) { + // two pauses à n ticks to achieve MIN_CMD_TICKS + *data++ = 0x00010001 * ((MIN_CMD_TICKS + 61) / 62); + } + *data = 0; + + // as the rmt is not running anymore, mark it as stopped + _rmtStopped = true; +} + +static void IRAM_ATTR apply_command(StepperQueue *q, bool fill_part_one, + uint32_t *data) { + if (!fill_part_one) { + data += PART_SIZE; + } + uint8_t rp = q->read_idx; + if (rp == q->next_write_idx) { + // no command in queue + if (fill_part_one) { + q->bufferContainsSteps[0] = false; + for (uint8_t i = 0; i < PART_SIZE; i++) { + // make a pause with approx. 1ms + // 258 ticks * 2 * 31 = 15996 @ 16MHz + // 347 ticks * 2 * 23 = 15962 @ 16MHz + *data++ = 0x010001 * (16000 / 2 / PART_SIZE); + } + } else { + q->stop_rmt(false); + } + return; + } + // Process command + struct queue_entry *e_curr = &q->entry[rp & QUEUE_LEN_MASK]; + + if (e_curr->toggle_dir) { + // the command requests dir pin toggle + // This is ok only, if the ongoing command does not contain steps + if (q->bufferContainsSteps[fill_part_one ? 1 : 0]) { + // So we need a pause. change the finished read entry into a pause + q->bufferContainsSteps[fill_part_one ? 0 : 1] = false; + for (uint8_t i = 0; i < PART_SIZE; i++) { + // two pauses à n ticks to achieve MIN_CMD_TICKS + *data++ = 0x00010001 * + ((MIN_CMD_TICKS + 2 * PART_SIZE - 1) / (2 * PART_SIZE)); + } + return; + } + // The ongoing command does not contain steps, so change dir here should be + // ok + gpio_num_t dirPin = (gpio_num_t)q->dirPin; + gpio_set_level(dirPin, gpio_get_level(dirPin) ^ 1); + // and delete the request + e_curr->toggle_dir = 0; + } + + uint8_t steps = e_curr->steps; + uint16_t ticks = e_curr->ticks; + // if (steps != 0) { + // PROBE_1_TOGGLE; + //} + uint32_t last_entry; + if (steps == 0) { + q->bufferContainsSteps[fill_part_one ? 0 : 1] = false; + // Perhaps the rmt performs look ahead + ticks -= (PART_SIZE - 2) * 4 + 8; + uint16_t ticks_l = ticks >> 1; + uint16_t ticks_r = ticks - ticks_l; + last_entry = ticks_l; + last_entry <<= 16; + last_entry |= ticks_r; + *data++ = last_entry; + for (uint8_t i = 1; i < PART_SIZE - 1; i++) { + *data++ = 0x00020002; + } + last_entry = 0x00040004; + } else { + q->bufferContainsSteps[fill_part_one ? 0 : 1] = true; + if (ticks == 0xffff) { + // special treatment for this case, because an rmt entry can only cover up + // to 0xfffe ticks every step must be minimum split into two rmt entries, + // so at max PART/2 steps can be done. + if (steps < PART_SIZE / 2) { + for (uint8_t i = 1; i < steps; i++) { + // steps-1 iterations + *data++ = 0x40007fff | 0x8000; + *data++ = 0x20002000; + } + *data++ = 0x40007fff | 0x8000; + uint16_t delta = PART_SIZE - 2 * steps; + delta <<= 5; + *data++ = 0x20002000 - delta; + // 2*(steps - 1) + 1 already stored => 2*steps - 1 + // and after this for loop one entry added => 2*steps + for (uint8_t i = 2 * steps; i < PART_SIZE - 1; i++) { + *data++ = 0x00100010; + } + last_entry = 0x00100010; + steps = 0; + } else { + steps -= PART_SIZE / 2; + for (uint8_t i = 0; i < PART_SIZE / 2 - 1; i++) { + *data++ = 0x40007fff | 0x8000; + *data++ = 0x20002000; + } + *data++ = 0x40007fff | 0x8000; + last_entry = 0x20002000; + } + } else if ((steps < 2 * PART_SIZE) && (steps != PART_SIZE)) { + uint8_t steps_to_do = steps; + if (steps > PART_SIZE) { + steps_to_do /= 2; + } + + uint16_t ticks_l = ticks >> 1; + uint16_t ticks_r = ticks - ticks_l; + uint32_t rmt_entry = ticks_l; + rmt_entry <<= 16; + rmt_entry |= ticks_r | 0x8000; // with step + for (uint8_t i = 1; i < steps_to_do; i++) { + *data++ = rmt_entry; + } + uint32_t delta = (PART_SIZE - steps_to_do) * 4 + 8; + delta <<= 16; // shift in upper 16bit + *data++ = rmt_entry - delta; + for (uint8_t i = steps_to_do; i < PART_SIZE - 1; i++) { + *data++ = 0x00020002; + } + last_entry = 0x00040004; + steps -= steps_to_do; + } else { + // either >= 2*PART_SIZE or = PART_SIZE + // every entry one step + uint16_t ticks_l = ticks >> 1; + uint16_t ticks_r = ticks - ticks_l; + uint32_t rmt_entry = ticks_l; + rmt_entry <<= 16; + rmt_entry |= ticks_r | 0x8000; // with step + for (uint8_t i = 0; i < PART_SIZE - 1; i++) { + *data++ = rmt_entry; + } + last_entry = rmt_entry; + steps -= PART_SIZE; + } + } + // No tick lost mentioned for esp32c3 + // if (!fill_part_one) { + // Note: When enabling the continuous transmission mode by setting + // RMT_REG_TX_CONTI_MODE, the transmitter will transmit the data on the + // channel continuously, that is, from the first byte to the last one, + // then from the first to the last again, and so on. In this mode, there + // will be an idle level lasting one clk_div cycle between N and N+1 + // transmissions. + // last_entry -= 1; + // } + *data = last_entry; + + // Data is complete + if (steps == 0) { + // The command has been completed + if (e_curr->repeat_entry == 0) { + q->read_idx = rp + 1; + } + } else { + e_curr->steps = steps; + } +} + +#if !defined(RMT_CHANNEL_MEM) && !defined(SUPPORT_ESP32C3_RMT) +#define RMT_LIMIT tx_lim +#define RMT_FIFO apb_fifo_mask +#else +#define RMT_LIMIT limit +#define RMT_FIFO fifo_mask +#endif + +// The threshold interrupts are happening in the "middle" of the previous entry. +// Best strategy: +// 1. enable threshold interrupt with PART_SIZE+2 +// 2. On every threshold interrupt toggle PART_SIZE and PART_SIZE+1 +// This way the first interrupt happens on the first entry of second half, +// and the second interrupt on the first entry of the first half. +// Afterwards alternating. This way the end interrupt is always "half buffer +// away" from the threshold interrupt +#ifdef TEST_MODE +#define PROCESS_CHANNEL(ch) \ + if (mask & RMT_CH##ch##_TX_END_INT_ST) { \ + PROBE_1_TOGGLE; \ + } \ + if (mask & RMT_CH##ch##_TX_THR_EVENT_INT_ST) { \ + uint8_t old_limit = RMT.tx_lim[ch].RMT_LIMIT; \ + if (old_limit == PART_SIZE + 1) { \ + /* second half of buffer sent */ \ + PROBE_2_TOGGLE; \ + /* demonstrate modification of RAM */ \ + uint32_t *mem = FAS_RMT_MEM(ch); \ + mem[PART_SIZE] = 0x33ff33ff; \ + RMT.tx_lim[ch].RMT_LIMIT = PART_SIZE; \ + } else { \ + /* first half of buffer sent */ \ + PROBE_3_TOGGLE; \ + RMT.tx_lim[ch].RMT_LIMIT = PART_SIZE + 1; \ + } \ + RMT.tx_conf[ch].conf_update = 1; \ + RMT.tx_conf[ch].conf_update = 0; \ + } +#else +#define PROCESS_CHANNEL(ch) \ + if (mask & RMT_CH##ch##_TX_END_INT_ST) { \ + StepperQueue *q = &fas_queue[QUEUES_MCPWM_PCNT + ch]; \ + disable_rmt_interrupts(q->channel); \ + q->_isRunning = false; \ + PROBE_1_TOGGLE; \ + PROBE_2_TOGGLE; \ + PROBE_3_TOGGLE; \ + } \ + if (mask & RMT_CH##ch##_TX_THR_EVENT_INT_ST) { \ + uint8_t old_limit = RMT.tx_lim[ch].RMT_LIMIT; \ + StepperQueue *q = &fas_queue[QUEUES_MCPWM_PCNT + ch]; \ + uint32_t *mem = FAS_RMT_MEM(ch); \ + if (old_limit == PART_SIZE + 1) { \ + /* second half of buffer sent */ \ + PROBE_2_TOGGLE; \ + apply_command(q, false, mem); \ + /* demonstrate modification of RAM */ \ + /*mem[PART_SIZE] = 0x33fff3ff; */ \ + RMT.tx_lim[ch].RMT_LIMIT = PART_SIZE; \ + } else { \ + /* first half of buffer sent */ \ + PROBE_3_TOGGLE; \ + apply_command(q, true, mem); \ + RMT.tx_lim[ch].RMT_LIMIT = PART_SIZE + 1; \ + } \ + RMT.tx_conf[ch].conf_update = 1; \ + RMT.tx_conf[ch].conf_update = 0; \ + } +#endif + +static void IRAM_ATTR tx_intr_handler(void *arg) { + uint32_t mask = RMT.int_st.val; + RMT.int_clr.val = mask; + PROCESS_CHANNEL(0); + PROCESS_CHANNEL(1); +#if QUEUES_RMT >= 4 + PROCESS_CHANNEL(2); + PROCESS_CHANNEL(3); +#endif +#if QUEUES_RMT == 8 + PROCESS_CHANNEL(4); + PROCESS_CHANNEL(5); + PROCESS_CHANNEL(6); + PROCESS_CHANNEL(7); +#endif +} + +void StepperQueue::init_rmt(uint8_t channel_num, uint8_t step_pin) { +#ifdef TEST_PROBE_1 + if (channel_num == 0) { + pinMode(TEST_PROBE_1, OUTPUT); + PROBE_1(HIGH); + delay(10); + PROBE_1(LOW); + delay(5); + PROBE_1(HIGH); + delay(5); + PROBE_1(LOW); + delay(5); + } +#endif +#ifdef TEST_PROBE_2 + pinMode(TEST_PROBE_2, OUTPUT); + PROBE_2(LOW); +#endif +#ifdef TEST_PROBE_3 + pinMode(TEST_PROBE_3, OUTPUT); + PROBE_3(LOW); +#endif + + _initVars(); + _step_pin = step_pin; + // digitalWrite(step_pin, LOW); + // pinMode(step_pin, OUTPUT); + + channel = (rmt_channel_t)channel_num; + + if (channel_num == 0) { + periph_module_enable(PERIPH_RMT_MODULE); + } + // APB_CLOCK=80 MHz + // CLK_DIV = APB_CLOCK/5 = 16 MHz + // + // Relation 1 in esp32c3 technical reference: + // 3 * T_APB + 5 * T_RMT_CLK < period * T_CLK_DIV + // => 8 * T_APB < period * T_APB*5 + // => period > 8/5 + // => period >= 2 + // + // Relation 2 in esp32c3 technical reference before end marker: + // 6 * T_APB + 12 * T_RMT_CLK < period * T_CLK_DIV + // => 18 * T_APB < period * T_APB*5 + // => period > 18/5 + // => period >= 4 + // + disable_rmt_interrupts(channel); + rmt_set_source_clk(channel, RMT_BASECLK_APB); + rmt_set_clk_div(channel, 5); + rmt_set_mem_block_num(channel, 1); + rmt_set_tx_carrier(channel, false, 0, 0, RMT_CARRIER_LEVEL_LOW); + rmt_tx_stop(channel); + rmt_tx_memory_reset(channel); + // rmt_rx_stop(channel); TX only channel ! + // rmt_tx_memory_reset is not defined in arduino V340 and based on test + // result not needed rmt_tx_memory_reset(channel); + if (channel_num == 0) { + rmt_isr_register(tx_intr_handler, NULL, + ESP_INTR_FLAG_SHARED | ESP_INTR_FLAG_IRAM, NULL); + RMT.sys_conf.fifo_mask = 1; // disable fifo mode + } + + _isRunning = false; + _rmtStopped = true; + + connect_rmt(); + +#ifdef TEST_MODE + if (channel == 0) { + RMT.tx_conf[channel].mem_rd_rst = 1; + RMT.tx_conf[channel].mem_rd_rst = 0; + uint32_t *mem = FAS_RMT_MEM(channel); + // Fill the buffer with a significant pattern for debugging + for (uint8_t i = 0; i < PART_SIZE; i++) { + *mem++ = 0x7fffffff; + } + for (uint8_t i = PART_SIZE; i < 2 * PART_SIZE; i++) { + *mem++ = 0x3fffdfff; + } + // without end marker it does not loop + *mem++ = 0; + *mem++ = 0; + + // conti mode is accepted with the conf_update 1 strobe + RMT.tx_conf[channel].tx_conti_mode = 1; + RMT.tx_conf[channel].conf_update = 1; + RMT.tx_conf[channel].conf_update = 0; + RMT.tx_conf[channel].mem_tx_wrap_en = 0; + RMT.tx_conf[channel].conf_update = 1; + RMT.tx_conf[channel].conf_update = 0; + enable_rmt_interrupts(channel); + // tx_start does not need conf_update + PROBE_1_TOGGLE; // end interrupt will toggle again PROBE_1 + RMT.tx_conf[channel].tx_start = 1; + + delay(1000); + if (false) { + mem--; + mem--; + // destroy end marker => no end interrupt, no repeat + *mem++ = 0x00010001; + *mem = 0x00010001; + } + if (true) { + // just clear conti mode => causes end interrupt, no repeat + RMT.tx_conf[channel].tx_conti_mode = 0; + RMT.tx_conf[channel].conf_update = 1; + RMT.tx_conf[channel].conf_update = 0; + } + delay(1000); + // actually no need to enable/disable interrupts. + // and this seems to avoid some pitfalls + + // This runs the RMT buffer once + RMT.tx_conf[channel].tx_conti_mode = 0; + RMT.tx_conf[channel].conf_update = 1; + RMT.tx_conf[channel].conf_update = 0; + RMT.tx_conf[channel].tx_start = 1; + while (true) { + delay(1000); + PROBE_1_TOGGLE; + } + } +#endif +} + +void StepperQueue::connect_rmt() { + RMT.tx_conf[channel].idle_out_lv = 0; + RMT.tx_conf[channel].idle_out_en = 1; + RMT.tx_conf[channel].conf_update = 1; + RMT.tx_conf[channel].conf_update = 0; + // RMT.tx_conf[channel].mem_tx_wrap_en = 0; +#ifndef __ESP32_IDF_V44__ + rmt_set_pin(channel, RMT_MODE_TX, (gpio_num_t)_step_pin); +#else + rmt_set_gpio(channel, RMT_MODE_TX, (gpio_num_t)_step_pin, false); +#endif + +#ifdef TEST_MODE + // here gpio is 0 + delay(1); + PROBE_3_TOGGLE; + RMT.tx_conf[channel].idle_out_lv = 1; + RMT.tx_conf[channel].conf_update = 1; + RMT.tx_conf[channel].conf_update = 0; + // here gpio is 1 + delay(2); + PROBE_3_TOGGLE; + RMT.tx_conf[channel].idle_out_lv = 0; + RMT.tx_conf[channel].conf_update = 1; + RMT.tx_conf[channel].conf_update = 0; + // here gpio is 0 + delay(2); + PROBE_3_TOGGLE; + RMT.tx_conf[channel].idle_out_en = 0; + RMT.tx_conf[channel].conf_update = 1; + RMT.tx_conf[channel].conf_update = 0; + // here gpio is 0 + delay(2); + PROBE_3_TOGGLE; + RMT.tx_conf[channel].idle_out_lv = 1; + RMT.tx_conf[channel].idle_out_en = 1; + RMT.tx_conf[channel].conf_update = 1; + RMT.tx_conf[channel].conf_update = 0; + // here gpio is 1 + delay(2); + PROBE_3_TOGGLE; + RMT.tx_conf[channel].idle_out_lv = 0; + RMT.tx_conf[channel].conf_update = 1; + RMT.tx_conf[channel].conf_update = 0; + // here gpio is 0 + delay(2); + PROBE_3_TOGGLE; +#endif +} + +void StepperQueue::disconnect_rmt() { + disable_rmt_interrupts(channel); +#ifndef __ESP32_IDF_V44__ +// rmt_set_pin(channel, RMT_MODE_TX, (gpio_num_t)-1); +#else +// rmt_set_gpio(channel, RMT_MODE_TX, GPIO_NUM_NC, false); +#endif + RMT.tx_conf[channel].idle_out_en = 0; + RMT.tx_conf[channel].conf_update = 1; + RMT.tx_conf[channel].conf_update = 0; +} + +void StepperQueue::startQueue_rmt() { +#ifdef TRACE + USBSerial.println("START"); +#endif +#ifdef TEST_PROBE_2 + PROBE_2(LOW); +#endif +#ifdef TEST_PROBE_3 + PROBE_3(LOW); +#endif +#if defined(TEST_PROBE_1) && defined(TEST_PROBE_2) && defined(TEST_PROBE_3) + delay(1); + PROBE_1_TOGGLE; + delay(1); + PROBE_1_TOGGLE; + delay(1); + PROBE_1_TOGGLE; + delay(1); + PROBE_2_TOGGLE; + delay(2); + PROBE_2_TOGGLE; + delay(2); + PROBE_3_TOGGLE; + delay(3); + PROBE_3_TOGGLE; + delay(3); +#endif + rmt_tx_stop(channel); + // rmt_rx_stop(channel); + RMT.tx_conf[channel].mem_rd_rst = 1; + RMT.tx_conf[channel].mem_rd_rst = 0; + uint32_t *mem = FAS_RMT_MEM(channel); +//#define TRACE +#ifdef TRACE + // Fill the buffer with a significant pattern for debugging + // Keep it for now + for (uint8_t i = 0; i < 2 * PART_SIZE; i += 2) { + // mem[i] = 0x0fff8fff; + // mem[i + 1] = 0x7fff8fff; + } +#endif + // Write end marker + mem[2 * PART_SIZE] = 0; + mem[2 * PART_SIZE + 1] = 0; + _isRunning = true; + _rmtStopped = false; + disable_rmt_interrupts(channel); + RMT.tx_conf[channel].mem_tx_wrap_en = 0; + RMT.tx_conf[channel].conf_update = 1; + RMT.tx_conf[channel].conf_update = 0; + +#ifdef TRACE + USBSerial.print("Queue:"); + USBSerial.print(read_idx); + USBSerial.print('/'); + USBSerial.println(next_write_idx); + for (uint8_t i = 0; i < RMT_MEM_SIZE; i++) { + USBSerial.print(i); + USBSerial.print(' '); + USBSerial.println(mem[i], HEX); + } +#endif + + // set dirpin toggle here + uint8_t rp = read_idx; + if (rp == next_write_idx) { + // nothing to do ? + // Should not happen, so bail + return; + } + if (entry[rp & QUEUE_LEN_MASK].toggle_dir) { + gpio_set_level((gpio_num_t)dirPin, gpio_get_level((gpio_num_t)dirPin) ^ 1); + entry[rp & QUEUE_LEN_MASK].toggle_dir = false; + } + + bufferContainsSteps[0] = true; + bufferContainsSteps[1] = true; + apply_command(this, true, mem); + +#ifdef TRACE + USBSerial.print(RMT.tx_conf[channel].val, BIN); + USBSerial.println(' '); + USBSerial.print(RMT.tx_conf[channel].mem_tx_wrap_en); + USBSerial.println(' '); + for (uint8_t i = 0; i < RMT_MEM_SIZE; i++) { + USBSerial.print(i); + USBSerial.print(' '); + USBSerial.println(mem[i], HEX); + } + if (!isRunning()) { + USBSerial.println("STOPPED 1"); + } +#endif + + apply_command(this, false, mem); + +#ifdef TRACE + USBSerial.print(RMT.tx_conf[channel].val, BIN); + USBSerial.print(' '); + USBSerial.print(RMT.tx_conf[channel].mem_tx_wrap_en); + USBSerial.println(' '); + + for (uint8_t i = 0; i < RMT_MEM_SIZE; i++) { + USBSerial.print(i); + USBSerial.print(' '); + USBSerial.println(mem[i], HEX); + } +#endif + enable_rmt_interrupts(channel); + +#ifdef TRACE + USBSerial.print("Interrupt enable:"); + USBSerial.println(RMT.int_ena.val, BIN); + USBSerial.print("Interrupt status:"); + USBSerial.println(RMT.int_st.val, BIN); + USBSerial.print("Threshold: 0x"); + USBSerial.println(RMT.tx_lim[channel].val, HEX); +#endif + + // This starts the rmt module + RMT.tx_conf[channel].tx_conti_mode = 1; + RMT.tx_conf[channel].conf_update = 1; + RMT.tx_conf[channel].conf_update = 0; + RMT.tx_conf[channel].mem_tx_wrap_en = 0; + RMT.tx_conf[channel].conf_update = 1; + RMT.tx_conf[channel].conf_update = 0; + + PROBE_1_TOGGLE; + RMT.tx_conf[channel].tx_start = 1; +} +void StepperQueue::forceStop_rmt() { + stop_rmt(true); + + // and empty the buffer + read_idx = next_write_idx; +} +bool StepperQueue::isReadyForCommands_rmt() { + if (_isRunning) { + return !_rmtStopped; + } + return true; +} +uint16_t StepperQueue::_getPerformedPulses_rmt() { return 0; } +#endif diff --git a/src/StepperISR_esp32s3_rmt.cpp b/src/StepperISR_esp32s3_rmt.cpp new file mode 100644 index 00000000..996e430f --- /dev/null +++ b/src/StepperISR_esp32s3_rmt.cpp @@ -0,0 +1,653 @@ +#include "StepperISR.h" +#ifdef SUPPORT_ESP32S3_RMT + +// #define TEST_MODE +// #define TRACE + +#include "test_probe.h" + +// The following concept is in use: +// +// The rmt buffer is split into two parts. +// Each part will hold one command (or part of). +// After the two parts an end marker is placed. +// +// Of these 32 bits, the low 16-bit entry is sent first and the high entry +// second. +// Every 16 bit entry defines with MSB the output level and the lower 15 bits +// the ticks. +// +// Important difference of esp32s3 (compared to esp32): +// - configuration updates need an conf_update strobe +// (apparently the manual is not correct by mentioning to set conf_update +// first) +// - if the end marker is hit in continuous mode, there is no end interrupt +// - there is no tick lost with the end marker +// - minimum periods as per relation 1 and 2 to be adhered to +// +// +#ifdef SUPPORT_ESP32S3_RMT +#define PART_SIZE 23 +#define RMT_MEM_SIZE 48 +#else +#error +#define PART_SIZE 31 +#define RMT_MEM_SIZE 64 +#endif + +// In order to avoid threshold/end interrupt on end, add one +#define enable_rmt_interrupts(channel) \ + { \ + RMT.chn_tx_lim[channel].RMT_LIMIT = PART_SIZE + 2; \ + RMT.chnconf0[channel].conf_update_n = 1; \ + RMT.chnconf0[channel].conf_update_n = 0; \ + RMT.int_clr.val |= 0x101 << channel; \ + RMT.int_ena.val |= 0x101 << channel; \ + } +#define disable_rmt_interrupts(channel) \ + { RMT.int_ena.val &= ~(0x101 << channel); } + +void IRAM_ATTR StepperQueue::stop_rmt(bool both) { + // We are stopping the rmt by letting it run into the end at high speed. + // + // disable the interrupts + // rmt_set_tx_intr_en(channel, false); + // rmt_set_tx_thr_intr_en(channel, false, 0); + + // stop esp32 rmt, by let it hit the end + RMT.chnconf0[channel].tx_conti_mode_n = 0; + RMT.chnconf0[channel].conf_update_n = 1; + RMT.chnconf0[channel].conf_update_n = 0; + + // replace second part of buffer with pauses + uint32_t *data = FAS_RMT_MEM(channel); + uint8_t start = both ? 0 : PART_SIZE; + data = &data[start]; + for (uint8_t i = start; i < 2 * PART_SIZE; i++) { + // two pauses à n ticks to achieve MIN_CMD_TICKS + *data++ = 0x00010001 * ((MIN_CMD_TICKS + 61) / 62); + } + *data = 0; + + // as the rmt is not running anymore, mark it as stopped + _rmtStopped = true; +} + +static void IRAM_ATTR apply_command(StepperQueue *q, bool fill_part_one, + uint32_t *data) { + if (!fill_part_one) { + data += PART_SIZE; + } + uint8_t rp = q->read_idx; + if (rp == q->next_write_idx) { + // no command in queue + if (fill_part_one) { + q->bufferContainsSteps[0] = false; + for (uint8_t i = 0; i < PART_SIZE; i++) { + // make a pause with approx. 1ms + // 258 ticks * 2 * 31 = 15996 @ 16MHz + // 347 ticks * 2 * 23 = 15962 @ 16MHz + *data++ = 0x010001 * (16000 / 2 / PART_SIZE); + } + } else { + q->stop_rmt(false); + } + return; + } + // Process command + struct queue_entry *e_curr = &q->entry[rp & QUEUE_LEN_MASK]; + + if (e_curr->toggle_dir) { + // the command requests dir pin toggle + // This is ok only, if the ongoing command does not contain steps + if (q->bufferContainsSteps[fill_part_one ? 1 : 0]) { + // So we need a pause. change the finished read entry into a pause + q->bufferContainsSteps[fill_part_one ? 0 : 1] = false; + for (uint8_t i = 0; i < PART_SIZE; i++) { + // two pauses à n ticks to achieve MIN_CMD_TICKS + *data++ = 0x00010001 * + ((MIN_CMD_TICKS + 2 * PART_SIZE - 1) / (2 * PART_SIZE)); + } + return; + } + // The ongoing command does not contain steps, so change dir here should be + // ok + gpio_num_t dirPin = (gpio_num_t)q->dirPin; + gpio_set_level(dirPin, gpio_get_level(dirPin) ^ 1); + // and delete the request + e_curr->toggle_dir = 0; + } + + uint8_t steps = e_curr->steps; + uint16_t ticks = e_curr->ticks; + // if (steps != 0) { + // PROBE_1_TOGGLE; + //} + uint32_t last_entry; + if (steps == 0) { + q->bufferContainsSteps[fill_part_one ? 0 : 1] = false; + // Perhaps the rmt performs look ahead + ticks -= (PART_SIZE - 2) * 4 + 8; + uint16_t ticks_l = ticks >> 1; + uint16_t ticks_r = ticks - ticks_l; + last_entry = ticks_l; + last_entry <<= 16; + last_entry |= ticks_r; + *data++ = last_entry; + for (uint8_t i = 1; i < PART_SIZE - 1; i++) { + *data++ = 0x00020002; + } + last_entry = 0x00040004; + } else { + q->bufferContainsSteps[fill_part_one ? 0 : 1] = true; + if (ticks == 0xffff) { + // special treatment for this case, because an rmt entry can only cover up + // to 0xfffe ticks every step must be minimum split into two rmt entries, + // so at max PART/2 steps can be done. + if (steps < PART_SIZE / 2) { + for (uint8_t i = 1; i < steps; i++) { + // steps-1 iterations + *data++ = 0x40007fff | 0x8000; + *data++ = 0x20002000; + } + *data++ = 0x40007fff | 0x8000; + uint16_t delta = PART_SIZE - 2 * steps; + delta <<= 5; + *data++ = 0x20002000 - delta; + // 2*(steps - 1) + 1 already stored => 2*steps - 1 + // and after this for loop one entry added => 2*steps + for (uint8_t i = 2 * steps; i < PART_SIZE - 1; i++) { + *data++ = 0x00100010; + } + last_entry = 0x00100010; + steps = 0; + } else { + steps -= PART_SIZE / 2; + for (uint8_t i = 0; i < PART_SIZE / 2 - 1; i++) { + *data++ = 0x40007fff | 0x8000; + *data++ = 0x20002000; + } + *data++ = 0x40007fff | 0x8000; + last_entry = 0x20002000; + } + } else if ((steps < 2 * PART_SIZE) && (steps != PART_SIZE)) { + uint8_t steps_to_do = steps; + if (steps > PART_SIZE) { + steps_to_do /= 2; + } + + uint16_t ticks_l = ticks >> 1; + uint16_t ticks_r = ticks - ticks_l; + uint32_t rmt_entry = ticks_l; + rmt_entry <<= 16; + rmt_entry |= ticks_r | 0x8000; // with step + for (uint8_t i = 1; i < steps_to_do; i++) { + *data++ = rmt_entry; + } + uint32_t delta = (PART_SIZE - steps_to_do) * 4 + 8; + delta <<= 16; // shift in upper 16bit + *data++ = rmt_entry - delta; + for (uint8_t i = steps_to_do; i < PART_SIZE - 1; i++) { + *data++ = 0x00020002; + } + last_entry = 0x00040004; + steps -= steps_to_do; + } else { + // either >= 2*PART_SIZE or = PART_SIZE + // every entry one step + uint16_t ticks_l = ticks >> 1; + uint16_t ticks_r = ticks - ticks_l; + uint32_t rmt_entry = ticks_l; + rmt_entry <<= 16; + rmt_entry |= ticks_r | 0x8000; // with step + for (uint8_t i = 0; i < PART_SIZE - 1; i++) { + *data++ = rmt_entry; + } + last_entry = rmt_entry; + steps -= PART_SIZE; + } + } + // No tick lost mentioned for esp32s3 + // if (!fill_part_one) { + // Note: When enabling the continuous transmission mode by setting + // RMT_REG_TX_CONTI_MODE, the transmitter will transmit the data on the + // channel continuously, that is, from the first byte to the last one, + // then from the first to the last again, and so on. In this mode, there + // will be an idle level lasting one clk_div cycle between N and N+1 + // transmissions. + // last_entry -= 1; + // } + *data = last_entry; + + // Data is complete + if (steps == 0) { + // The command has been completed + if (e_curr->repeat_entry == 0) { + q->read_idx = rp + 1; + } + } else { + e_curr->steps = steps; + } +} + +#if !defined(RMT_CHANNEL_MEM) && !defined(SUPPORT_ESP32S3_RMT) +#define RMT_LIMIT tx_lim +#define RMT_FIFO apb_fifo_mask +#else +#define RMT_LIMIT tx_lim_chn +#define RMT_FIFO apb_fifo_mask +#endif + +// The threshold interrupts are happening in the "middle" of the previous entry. +// Best strategy: +// 1. enable threshold interrupt with PART_SIZE+2 +// 2. On every threshold interrupt toggle PART_SIZE and PART_SIZE+1 +// This way the first interrupt happens on the first entry of second half, +// and the second interrupt on the first entry of the first half. +// Afterwards alternating. This way the end interrupt is always "half buffer +// away" from the threshold interrupt +#ifdef TEST_MODE +#define PROCESS_CHANNEL(ch) \ + if (mask & RMT_CH##ch##_TX_END_INT_ST) { \ + PROBE_1_TOGGLE; \ + } \ + if (mask & RMT_CH##ch##_TX_THR_EVENT_INT_ST) { \ + uint8_t old_limit = RMT.chn_tx_lim[ch].RMT_LIMIT; \ + if (old_limit == PART_SIZE + 1) { \ + /* second half of buffer sent */ \ + PROBE_2_TOGGLE; \ + /* demonstrate modification of RAM */ \ + uint32_t *mem = FAS_RMT_MEM(ch); \ + mem[PART_SIZE] = 0x33ff33ff; \ + RMT.chn_tx_lim[ch].RMT_LIMIT = PART_SIZE; \ + } else { \ + /* first half of buffer sent */ \ + PROBE_3_TOGGLE; \ + RMT.chn_tx_lim[ch].RMT_LIMIT = PART_SIZE + 1; \ + } \ + RMT.chnconf0[ch].conf_update_n = 1; \ + RMT.chnconf0[ch].conf_update_n = 0; \ + } +#else +#define PROCESS_CHANNEL(ch) \ + if (mask & RMT_CH##ch##_TX_END_INT_ST) { \ + StepperQueue *q = &fas_queue[QUEUES_MCPWM_PCNT + ch]; \ + disable_rmt_interrupts(q->channel); \ + q->_isRunning = false; \ + PROBE_1_TOGGLE; \ + PROBE_2_TOGGLE; \ + PROBE_3_TOGGLE; \ + } \ + if (mask & RMT_CH##ch##_TX_THR_EVENT_INT_ST) { \ + uint8_t old_limit = RMT.chn_tx_lim[ch].RMT_LIMIT; \ + StepperQueue *q = &fas_queue[QUEUES_MCPWM_PCNT + ch]; \ + uint32_t *mem = FAS_RMT_MEM(ch); \ + if (old_limit == PART_SIZE + 1) { \ + /* second half of buffer sent */ \ + PROBE_2_TOGGLE; \ + apply_command(q, false, mem); \ + /* demonstrate modification of RAM */ \ + /*mem[PART_SIZE] = 0x33fff3ff; */ \ + RMT.chn_tx_lim[ch].RMT_LIMIT = PART_SIZE; \ + } else { \ + /* first half of buffer sent */ \ + PROBE_3_TOGGLE; \ + apply_command(q, true, mem); \ + RMT.chn_tx_lim[ch].RMT_LIMIT = PART_SIZE + 1; \ + } \ + RMT.chnconf0[ch].conf_update_n = 1; \ + RMT.chnconf0[ch].conf_update_n = 0; \ + } +#endif + +static void IRAM_ATTR tx_intr_handler(void *arg) { + uint32_t mask = RMT.int_st.val; + RMT.int_clr.val = mask; + PROCESS_CHANNEL(0); + PROCESS_CHANNEL(1); +#if QUEUES_RMT >= 4 + PROCESS_CHANNEL(2); + PROCESS_CHANNEL(3); +#endif +#if QUEUES_RMT == 8 + PROCESS_CHANNEL(4); + PROCESS_CHANNEL(5); + PROCESS_CHANNEL(6); + PROCESS_CHANNEL(7); +#endif +} + +void StepperQueue::init_rmt(uint8_t channel_num, uint8_t step_pin) { +#ifdef TEST_PROBE_1 + if (channel_num == 0) { + pinMode(TEST_PROBE_1, OUTPUT); + PROBE_1(HIGH); + delay(10); + PROBE_1(LOW); + delay(5); + PROBE_1(HIGH); + delay(5); + PROBE_1(LOW); + delay(5); + } +#endif +#ifdef TEST_PROBE_2 + pinMode(TEST_PROBE_2, OUTPUT); + PROBE_2(LOW); +#endif +#ifdef TEST_PROBE_3 + pinMode(TEST_PROBE_3, OUTPUT); + PROBE_3(LOW); +#endif + + _initVars(); + _step_pin = step_pin; + // digitalWrite(step_pin, LOW); + // pinMode(step_pin, OUTPUT); + + channel = (rmt_channel_t)channel_num; + + if (channel_num == 0) { + periph_module_enable(PERIPH_RMT_MODULE); + } + // APB_CLOCK=80 MHz + // CLK_DIV = APB_CLOCK/5 = 16 MHz + // + // Relation 1 in esp32s3 technical reference: + // 3 * T_APB + 5 * T_RMT_CLK < period * T_CLK_DIV + // => 8 * T_APB < period * T_APB*5 + // => period > 8/5 + // => period >= 2 + // + // Relation 2 in esp32s3 technical reference before end marker: + // 6 * T_APB + 12 * T_RMT_CLK < period * T_CLK_DIV + // => 18 * T_APB < period * T_APB*5 + // => period > 18/5 + // => period >= 4 + // + disable_rmt_interrupts(channel); + rmt_set_source_clk(channel, RMT_BASECLK_APB); + rmt_set_clk_div(channel, 5); + rmt_set_mem_block_num(channel, 1); + rmt_set_tx_carrier(channel, false, 0, 0, RMT_CARRIER_LEVEL_LOW); + rmt_tx_stop(channel); + rmt_tx_memory_reset(channel); + // rmt_rx_stop(channel); TX only channel ! + // rmt_tx_memory_reset is not defined in arduino V340 and based on test + // result not needed rmt_tx_memory_reset(channel); + if (channel_num == 0) { + rmt_isr_register(tx_intr_handler, NULL, + ESP_INTR_FLAG_SHARED | ESP_INTR_FLAG_IRAM, NULL); + RMT.sys_conf.apb_fifo_mask = 1; // disable fifo mode + } + + _isRunning = false; + _rmtStopped = true; + + connect_rmt(); + +#ifdef TEST_MODE + if (channel == 0) { + RMT.chnconf0[channel].mem_rd_rst_n = 1; + RMT.chnconf0[channel].mem_rd_rst_n = 0; + uint32_t *mem = FAS_RMT_MEM(channel); + // Fill the buffer with a significant pattern for debugging + for (uint8_t i = 0; i < PART_SIZE; i++) { + *mem++ = 0x7fffffff; + } + for (uint8_t i = PART_SIZE; i < 2 * PART_SIZE; i++) { + *mem++ = 0x3fffdfff; + } + // without end marker it does not loop + *mem++ = 0; + *mem++ = 0; + + // conti mode is accepted with the conf_update 1 strobe + RMT.chnconf0[channel].tx_conti_mode_n = 1; + RMT.chnconf0[channel].conf_update_n = 1; + RMT.chnconf0[channel].conf_update_n = 0; + RMT.chnconf0[channel].mem_tx_wrap_en_n = 0; + RMT.chnconf0[channel].conf_update_n = 1; + RMT.chnconf0[channel].conf_update_n = 0; + enable_rmt_interrupts(channel); + // tx_start does not need conf_update + PROBE_1_TOGGLE; // end interrupt will toggle again PROBE_1 + RMT.chnconf0[channel].tx_start_n = 1; + + delay(1000); + if (false) { + mem--; + mem--; + // destroy end marker => no end interrupt, no repeat + *mem++ = 0x00010001; + *mem = 0x00010001; + } + if (true) { + // just clear conti mode => causes end interrupt, no repeat + RMT.chnconf0[channel].tx_conti_mode_n = 0; + RMT.chnconf0[channel].conf_update_n = 1; + RMT.chnconf0[channel].conf_update_n = 0; + } + delay(1000); + // actually no need to enable/disable interrupts. + // and this seems to avoid some pitfalls + + // This runs the RMT buffer once + RMT.chnconf0[channel].tx_conti_mode_n = 0; + RMT.chnconf0[channel].conf_update_n = 1; + RMT.chnconf0[channel].conf_update_n = 0; + RMT.chnconf0[channel].tx_start_n = 1; + while (true) { + delay(1000); + PROBE_1_TOGGLE; + } + } +#endif +} + +void StepperQueue::connect_rmt() { + RMT.chnconf0[channel].idle_out_lv_n = 0; + RMT.chnconf0[channel].idle_out_en_n = 1; + RMT.chnconf0[channel].conf_update_n = 1; + RMT.chnconf0[channel].conf_update_n = 0; + // RMT.tx_conf[channel].mem_tx_wrap_en = 0; +#ifndef __ESP32_IDF_V44__ + rmt_set_pin(channel, RMT_MODE_TX, (gpio_num_t)_step_pin); +#else + rmt_set_gpio(channel, RMT_MODE_TX, (gpio_num_t)_step_pin, false); +#endif + +#ifdef TEST_MODE + // here gpio is 0 + delay(1); + PROBE_3_TOGGLE; + RMT.tx_conf[channel].idle_out_lv_n = 1; + RMT.tx_conf[channel].conf_update_n = 1; + RMT.tx_conf[channel].conf_update_n = 0; + // here gpio is 1 + delay(2); + PROBE_3_TOGGLE; + RMT.chnconf0[channel].idle_out_lv_n = 0; + RMT.chnconf0[channel].conf_update_n = 1; + RMT.chnconf0[channel].conf_update_n = 0; + // here gpio is 0 + delay(2); + PROBE_3_TOGGLE; + RMT.chnconf0[channel].idle_out_en_n = 0; + RMT.chnconf0[channel].conf_update_n = 1; + RMT.chnconf0[channel].conf_update_n = 0; + // here gpio is 0 + delay(2); + PROBE_3_TOGGLE; + RMT.chnconf0[channel].idle_out_lv_n = 1; + RMT.chnconf0[channel].idle_out_en_n = 1; + RMT.chnconf0[channel].conf_update_n = 1; + RMT.chnconf0[channel].conf_update_n = 0; + // here gpio is 1 + delay(2); + PROBE_3_TOGGLE; + RMT.chnconf0[channel].idle_out_lv_n = 0; + RMT.chnconf0[channel].conf_update_n = 1; + RMT.chnconf0[channel].conf_update_n = 0; + // here gpio is 0 + delay(2); + PROBE_3_TOGGLE; +#endif +} + +void StepperQueue::disconnect_rmt() { + disable_rmt_interrupts(channel); +#ifndef __ESP32_IDF_V44__ +// rmt_set_pin(channel, RMT_MODE_TX, (gpio_num_t)-1); +#else +// rmt_set_gpio(channel, RMT_MODE_TX, GPIO_NUM_NC, false); +#endif + RMT.chnconf0[channel].idle_out_en_n = 0; + RMT.chnconf0[channel].conf_update_n = 1; + RMT.chnconf0[channel].conf_update_n = 0; +} + +void StepperQueue::startQueue_rmt() { +#ifdef TRACE + USBSerial.println("START"); +#endif +#ifdef TEST_PROBE_2 + PROBE_2(LOW); +#endif +#ifdef TEST_PROBE_3 + PROBE_3(LOW); +#endif +#if defined(TEST_PROBE_1) && defined(TEST_PROBE_2) && defined(TEST_PROBE_3) + delay(1); + PROBE_1_TOGGLE; + delay(1); + PROBE_1_TOGGLE; + delay(1); + PROBE_1_TOGGLE; + delay(1); + PROBE_2_TOGGLE; + delay(2); + PROBE_2_TOGGLE; + delay(2); + PROBE_3_TOGGLE; + delay(3); + PROBE_3_TOGGLE; + delay(3); +#endif + rmt_tx_stop(channel); + // rmt_rx_stop(channel); + RMT.chnconf0[channel].mem_rd_rst_n = 1; + RMT.chnconf0[channel].mem_rd_rst_n = 0; + uint32_t *mem = FAS_RMT_MEM(channel); +// #define TRACE +#ifdef TRACE + // Fill the buffer with a significant pattern for debugging + // Keep it for now + for (uint8_t i = 0; i < 2 * PART_SIZE; i += 2) { + // mem[i] = 0x0fff8fff; + // mem[i + 1] = 0x7fff8fff; + } +#endif + // Write end marker + mem[2 * PART_SIZE] = 0; + mem[2 * PART_SIZE + 1] = 0; + _isRunning = true; + _rmtStopped = false; + disable_rmt_interrupts(channel); + RMT.chnconf0[channel].mem_tx_wrap_en_n = 0; + RMT.chnconf0[channel].conf_update_n = 1; + RMT.chnconf0[channel].conf_update_n = 0; + +#ifdef TRACE + USBSerial.print("Queue:"); + USBSerial.print(read_idx); + USBSerial.print('/'); + USBSerial.println(next_write_idx); + for (uint8_t i = 0; i < RMT_MEM_SIZE; i++) { + USBSerial.print(i); + USBSerial.print(' '); + USBSerial.println(mem[i], HEX); + } +#endif + + // set dirpin toggle here + uint8_t rp = read_idx; + if (rp == next_write_idx) { + // nothing to do ? + // Should not happen, so bail + return; + } + if (entry[rp & QUEUE_LEN_MASK].toggle_dir) { + gpio_set_level((gpio_num_t)dirPin, gpio_get_level((gpio_num_t)dirPin) ^ 1); + entry[rp & QUEUE_LEN_MASK].toggle_dir = false; + } + + bufferContainsSteps[0] = true; + bufferContainsSteps[1] = true; + apply_command(this, true, mem); + +#ifdef TRACE + USBSerial.print(RMT.chnconf0[channel].val, BIN); + USBSerial.println(' '); + USBSerial.print(RMT.chnconf0[channel].mem_tx_wrap_en_n); + USBSerial.println(' '); + for (uint8_t i = 0; i < RMT_MEM_SIZE; i++) { + USBSerial.print(i); + USBSerial.print(' '); + USBSerial.println(mem[i], HEX); + } + if (!isRunning()) { + USBSerial.println("STOPPED 1"); + } +#endif + + apply_command(this, false, mem); + +#ifdef TRACE + USBSerial.print(RMT.chnconf0[channel].val, BIN); + USBSerial.print(' '); + USBSerial.print(RMT.chnconf0[channel].mem_tx_wrap_en_n); + USBSerial.println(' '); + + for (uint8_t i = 0; i < RMT_MEM_SIZE; i++) { + USBSerial.print(i); + USBSerial.print(' '); + USBSerial.println(mem[i], HEX); + } +#endif + enable_rmt_interrupts(channel); + +#ifdef TRACE + USBSerial.print("Interrupt enable:"); + USBSerial.println(RMT.int_ena.val, BIN); + USBSerial.print("Interrupt status:"); + USBSerial.println(RMT.int_st.val, BIN); + USBSerial.print("Threshold: 0x"); + USBSerial.println(RMT.tx_lim[channel].val, HEX); +#endif + + // This starts the rmt module + RMT.chnconf0[channel].tx_conti_mode_n = 1; + RMT.chnconf0[channel].conf_update_n = 1; + RMT.chnconf0[channel].conf_update_n = 0; + RMT.chnconf0[channel].mem_tx_wrap_en_n = 0; + RMT.chnconf0[channel].conf_update_n = 1; + RMT.chnconf0[channel].conf_update_n = 0; + + PROBE_1_TOGGLE; + RMT.chnconf0[channel].tx_start_n = 1; +} +void StepperQueue::forceStop_rmt() { + stop_rmt(true); + + // and empty the buffer + read_idx = next_write_idx; +} +bool StepperQueue::isReadyForCommands_rmt() { + if (_isRunning) { + return !_rmtStopped; + } + return true; +} +uint16_t StepperQueue::_getPerformedPulses_rmt() { return 0; } +#endif diff --git a/src/common.h b/src/fas_common.h similarity index 92% rename from src/common.h rename to src/fas_common.h index 5a2d0c80..2a4dfc4f 100644 --- a/src/common.h +++ b/src/fas_common.h @@ -16,6 +16,11 @@ struct stepper_command_s { bool count_up; }; +struct actual_ticks_s { + uint32_t ticks; // ticks == 0 means standstill + bool count_up; +}; + struct queue_end_s { volatile int32_t pos; // in steps volatile bool count_up; @@ -50,6 +55,7 @@ struct queue_end_s { #include #include #include + #include "../extras/tests/pc_based/stubs.h" // For pc-based testing, the macro TEST is defined. The pc-based testing does @@ -74,6 +80,7 @@ struct queue_end_s { #define MIN_DIR_DELAY_US (MIN_CMD_TICKS / (TICKS_PER_S / 1000000)) #define MAX_DIR_DELAY_US (65535 / (TICKS_PER_S / 1000000)) #define DELAY_MS_BASE 1 +#define SUPPORT_UNSAFE_ABS_SPEED_LIMIT_SETTING 0 #define noop_or_wait @@ -91,6 +98,7 @@ struct queue_end_s { #define SUPPORT_ESP32 #define SUPPORT_EXTERNAL_DIRECTION_PIN +#define SUPPORT_UNSAFE_ABS_SPEED_LIMIT_SETTING 1 // Some more esp32 specific includes #include @@ -110,7 +118,6 @@ struct queue_end_s { #include #include -#define SUPPORT_SELECT_DRIVER_TYPE #define SUPPORT_ESP32_MCPWM_PCNT #define SUPPORT_ESP32_RMT #include @@ -129,8 +136,8 @@ struct queue_end_s { #elif CONFIG_IDF_TARGET_ESP32S2 #define SUPPORT_ESP32S3_PULSE_COUNTER #define SUPPORT_ESP32_RMT -#include #include +#include #include #include #include @@ -140,7 +147,7 @@ struct queue_end_s { //========================================================================== // -// ESP32 derivate - ESP32S3 - NOT SUPPORTED +// ESP32 derivate - ESP32S3 // //========================================================================== #elif CONFIG_IDF_TARGET_ESP32S3 @@ -153,21 +160,29 @@ struct queue_end_s { #include #include +#define SUPPORT_ESP32_RMT +#define SUPPORT_ESP32S3_RMT +#include #include +#include +#include +#include +#define FAS_RMT_MEM(channel) ((uint32_t *)RMTMEM.chan[channel].data32) + #define QUEUES_MCPWM_PCNT 4 -#define QUEUES_RMT 0 +#define QUEUES_RMT 4 // have support for pulse counter #define SUPPORT_ESP32_PULSE_COUNTER //========================================================================== // -// ESP32 derivate - ESP32C3 - NOT SUPPORTED +// ESP32 derivate - ESP32C3 // //========================================================================== #elif CONFIG_IDF_TARGET_ESP32C3 -#error "esp32c3 is not supported" #define SUPPORT_ESP32_RMT +#define SUPPORT_ESP32C3_RMT #include #include #include @@ -175,6 +190,7 @@ struct queue_end_s { #include #define QUEUES_MCPWM_PCNT 0 #define QUEUES_RMT 2 +#define FAS_RMT_MEM(channel) ((uint32_t *)RMTMEM.chan[channel].data32) //========================================================================== // @@ -231,6 +247,7 @@ struct queue_end_s { #elif defined(ESP_PLATFORM) #define SUPPORT_ESP32 +#define SUPPORT_UNSAFE_ABS_SPEED_LIMIT_SETTING 1 // esp32 specific includes #include @@ -331,9 +348,11 @@ struct queue_end_s { //========================================================================== #elif defined(ARDUINO_ARCH_AVR) #define SUPPORT_AVR +#define SUPPORT_UNSAFE_ABS_SPEED_LIMIT_SETTING 1 // this is an arduino platform, so include the Arduino.h header file #include + #include "AVRStepperPins.h" // for AVR processors a reentrant version of disabling/enabling interrupts is // used @@ -356,7 +375,7 @@ struct queue_end_s { #define noop_or_wait -#define SUPPORT_DIR_PIN_MASK uint8_t +#define SUPPORT_DIR_TOGGLE_PIN_MASK uint8_t #define SUPPORT_QUEUE_ENTRY_END_POS_U16 @@ -422,4 +441,12 @@ enum channels { channelA, channelB, channelC }; #include #endif /* __ESP32_IDF_V44__ */ +//========================================================================== +// determine, if driver type selection should be supported +#if defined(QUEUES_MCPWM_PCNT) && defined(QUEUES_RMT) +#if (QUEUES_MCPWM_PCNT > 0) && (QUEUES_RMT > 0) +#define SUPPORT_SELECT_DRIVER_TYPE +#endif +#endif + #endif /* COMMON_H */ diff --git a/src/test_probe.h b/src/test_probe.h index bb2f2ee4..5ccbfab2 100644 --- a/src/test_probe.h +++ b/src/test_probe.h @@ -5,19 +5,26 @@ // code to investigate rmt module functioning //#define ESP32_TEST_PROBE - -#ifdef ESP32_TEST_PROBE +//#define ESP32C3_TEST_PROBE // in rmt: // TEST_PROBE_1 on startQueue and queue stop, with double toggle at // startQueue TEST_PROBE_2 end interrupt, when rmt transmission hits buffer // end TEST_PROBE_3 threshold interrupt, after first buffer half transmission // is complete + +#ifdef ESP32_TEST_PROBE #define TEST_PROBE_1 18 #define TEST_PROBE_2 5 #define TEST_PROBE_3 4 #endif +#ifdef ESP32C3_TEST_PROBE +#define TEST_PROBE_1 1 +#define TEST_PROBE_2 2 +#define TEST_PROBE_3 3 +#endif + #ifdef TEST_PROBE_1 #define PROBE_1(x) digitalWrite(TEST_PROBE_1, x) #define PROBE_1_TOGGLE \