Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
9 changes: 5 additions & 4 deletions .github/workflows/build_arduino_examples_matrix.yml
Original file line number Diff line number Diff line change
Expand Up @@ -10,10 +10,6 @@ on:
pull_request:
branches: [ master ]

concurrency:
group: ${{ github.workflow }}-${{ github.ref }}
cancel-in-progress: true

jobs:
build:
strategy:
Expand Down Expand Up @@ -80,6 +76,11 @@ jobs:
- atmelsam
- rpipico
- rpipico2
- bluepill_f103c8
- nucleo_g070rb
- blackpill_f401cc
- nucleo_h743zi
- nucleo_l476rg

runs-on: ubuntu-latest

Expand Down
4 changes: 0 additions & 4 deletions .github/workflows/build_idf_examples_matrix.yml
Original file line number Diff line number Diff line change
Expand Up @@ -15,10 +15,6 @@ on:
pull_request:
branches: [ master ]

concurrency:
group: ${{ github.workflow }}-${{ github.ref }}
cancel-in-progress: true

jobs:
build:
strategy:
Expand Down
43 changes: 43 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -639,6 +639,49 @@ Found on youtube:
As mentioned by kthod861 in [Issue #110](https://github.com/gin66/FastAccelStepper/issues/110):
* [22 01 2021 Stepper POC3](https://youtu.be/fm2_VkUG10k)

## STM32 Arduino Support

FastAccelStepper supports STM32 microcontrollers via the official
[Arduino Core STM32](https://github.com/stm32duino/Arduino_Core_STM32).

### Architecture

- **Step generation**: TIM2 CC interrupt + BSRR/BRR GPIO (push-pull OUTPUT)
- **Steppers**: Up to 4 (any GPIO pins, dynamic slot allocation)
- **Pulse width**: 6 µs (configurable via `STEP_PULSE_WIDTH_US`)
- **Cyclic fill**: PendSV exception, triggered from TIM2 ISR every 3ms via uwTick
- **GPIO mode**: Standard push-pull OUTPUT (any GPIO pin works)
- **Direction**: Atomic BSRR set/reset — not ODR XOR (race-free)
- **Direction settling**: `_dir_delay_active` state machine, 30µs delay
- **TIM2 clock**: Auto-detection with APB1 prescaler ×2 correction
- **Interrupt safety**: PRIMASK save/restore (reentrant)
- **SR handling**: Snapshot → clear all processed at once (rc_w0)
- **PendSV**: `__attribute__((weak))` — FreeRTOS compatible

### Default Pin Mapping

| Stepper | Default Pin | Notes |
|---------|-------------|-------|
| 0 | PA0 | Any GPIO pin can be used |
| 1 | PA1 | (PA0-PA3 are conventional only) |
| 2 | PA2 | |
| 3 | PA3 | |

### ⚠ Warnings

1. **No FreeRTOS** — PendSV is overridden (weak, FreeRTOS can override).
2. **TIM2 is reserved** — Do not use TIM2 elsewhere.
3. **HAL timebase must be SysTick** (default). uwTick is used for cyclic fill.
4. **Do not call HAL_Delay() with steppers running** — TIM2 priority 0 may preempt SysTick. Use millis() polling.
5. **TICKS_PER_S must match TIM2 counter clock** — Define before library includes:
```cpp
#define TICKS_PER_S 72000000UL // STM32F103 @72MHz
#include <FastAccelStepper.h>
```
See `pd_stm32/pd_config.h` for examples for each board.
6. **Clock error**: After `engine.init()`, check `fas_stm32_clock_error`:
if non-zero, `TICKS_PER_S` exceeds actual TIM2 clock.

## Contribution

- Thanks ixil for pull request (https://github.com/gin66/FastAccelStepper/pull/19) for ATmega2560
Expand Down
34 changes: 34 additions & 0 deletions extras/StepperPins_stm32.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
#ifndef STEPPERPINS_STM32_H
#define STEPPERPINS_STM32_H

// ====================================================================
// Default step pin mapping for STM32 platforms
//
// These defaults map steppers 0-3 to PA0-PA3 (TIM2 channels 1-4).
// Override by defining before including this header:
//
// #define STEP_PIN_STEPPER_0 PB0
// #include "StepperPins_stm32.h"
//
// Note: On STM32, any GPIO pin can be used as a step pin.
// PA0-PA3 are only a convention — the timer is used only for
// interrupt timing, not direct pin output.
// ====================================================================

#ifndef STEP_PIN_STEPPER_0
#define STEP_PIN_STEPPER_0 PA0
#endif

#ifndef STEP_PIN_STEPPER_1
#define STEP_PIN_STEPPER_1 PA1
#endif

#ifndef STEP_PIN_STEPPER_2
#define STEP_PIN_STEPPER_2 PA2
#endif

#ifndef STEP_PIN_STEPPER_3
#define STEP_PIN_STEPPER_3 PA3
#endif

#endif /* STEPPERPINS_STM32_H */
36 changes: 36 additions & 0 deletions extras/ci/build_matrix.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -152,6 +152,12 @@ templates:
framework: arduino
lib_extra_dirs: .

stm32:
platform: ststm32
framework: arduino
build_flags: ["-Wall"]
lib_extra_dirs: .

environments:
esp32:
template: esp32_arduino
Expand Down Expand Up @@ -285,6 +291,31 @@ environments:
board_upload_psram_length: 1048576
build_flags: ["-D__FREERTOS=1"]

bluepill_f103c8:
template: stm32
board: bluepill_f103c8
build_flags_extra: ["-DTICKS_PER_S=72000000UL"]

nucleo_g070rb:
template: stm32
board: nucleo_g070rb
build_flags_extra: ["-DTICKS_PER_S=64000000UL"]

blackpill_f401cc:
template: stm32
board: blackpill_f401cc
build_flags_extra: ["-DTICKS_PER_S=84000000UL"]

nucleo_h743zi:
template: stm32
board: nucleo_h743zi
build_flags_extra: ["-DTICKS_PER_S=240000000UL"]

nucleo_l476rg:
template: stm32
board: nucleo_l476rg
build_flags_extra: ["-DTICKS_PER_S=80000000UL"]

versioned_environments:
esp32:
prefix: esp32
Expand Down Expand Up @@ -429,6 +460,11 @@ workflows:
- atmelsam
- rpipico
- rpipico2
- bluepill_f103c8
- nucleo_g070rb
- blackpill_f401cc
- nucleo_h743zi
- nucleo_l476rg
script: build-platformio.sh

idf:
Expand Down
35 changes: 35 additions & 0 deletions extras/ci/platformio.ini
Original file line number Diff line number Diff line change
Expand Up @@ -195,6 +195,41 @@ build_flags = -D__FREERTOS=1
lib_extra_dirs = .
board_upload.psram_length = 1048576

[env:bluepill_f103c8]
platform = ststm32
board = bluepill_f103c8
framework = arduino
build_flags = -Wall -DTICKS_PER_S=72000000UL
lib_extra_dirs = .

[env:nucleo_g070rb]
platform = ststm32
board = nucleo_g070rb
framework = arduino
build_flags = -Wall -DTICKS_PER_S=64000000UL
lib_extra_dirs = .

[env:blackpill_f401cc]
platform = ststm32
board = blackpill_f401cc
framework = arduino
build_flags = -Wall -DTICKS_PER_S=84000000UL
lib_extra_dirs = .

[env:nucleo_h743zi]
platform = ststm32
board = nucleo_h743zi
framework = arduino
build_flags = -Wall -DTICKS_PER_S=240000000UL
lib_extra_dirs = .

[env:nucleo_l476rg]
platform = ststm32
board = nucleo_l476rg
framework = arduino
build_flags = -Wall -DTICKS_PER_S=80000000UL
lib_extra_dirs = .

[env:esp32_V6_13_0]
platform = espressif32 @ 6.13.0
board = esp32dev
Expand Down
8 changes: 4 additions & 4 deletions library.properties
Original file line number Diff line number Diff line change
Expand Up @@ -3,10 +3,10 @@ version=1.2.5
license=MIT
author=Jochen Kiemes <jochen@kiemes.de>
maintainer=Jochen Kiemes <jochen@kiemes.de>
sentence=A high speed stepper library for Atmega 168/168p/328/328p (nano), 32u4 (leonardo), 2560, ESP32, ESP32S2, ESP32S3, ESP32C3, ESP32C6, Atmel SAM Due, Raspberry pi pico and pico 2
paragraph=Drive stepper motors with acceleration/deceleration profile up to 50 kSteps/s (Atmega) and 200kSteps/s (esp32).
sentence=A high speed stepper library for Atmega 168/168p/328/328p (nano), 32u4 (leonardo), 2560, ESP32, ESP32S2, ESP32S3, ESP32C3, ESP32C6, Atmel SAM Due, Raspberry pi pico and pico 2, and STM32
paragraph=Drive stepper motors with acceleration/deceleration profile up to 50 kSteps/s (Atmega) and 200kSteps/s (esp32). Supports STM32F1/F4/G0/H7 series via STM32duino core.
url=https://github.com/gin66/FastAccelStepper
repository=https://github.com/gin66/FastAccelStepper.git
architectures=avr,esp32,sam,rp2040,rp2350
architectures=avr,esp32,sam,rp2040,rp2350,stm32
category=Device Control
dot_a_linkage=true
dot_a_linkage=true
21 changes: 21 additions & 0 deletions src/fas_arch/arduino_stm32.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
#ifndef FAS_ARCH_ARDUINO_STM32_H
#define FAS_ARCH_ARDUINO_STM32_H

#define FAS_STM32

#include <Arduino.h>
#include <stdint.h>
#include <stdlib.h>

// PRIMASK reentrant-safe interrupt control
// Saves and restores PRIMASK to support nested disable/enable calls
#define fasDisableInterrupts() \
uint32_t __fas_prim = __get_PRIMASK(); __disable_irq()
#define fasEnableInterrupts() \
__set_PRIMASK(__fas_prim)

#define FAS_PSTR(s) (s)
// PIN_UNDEFINED (255) and PIN_EXTERNAL_FLAG (128) are defined in
// FastAccelStepper.h. Do NOT redefine here to avoid -Wmacro-redefined.

#endif /* FAS_ARCH_ARDUINO_STM32_H */
5 changes: 5 additions & 0 deletions src/fas_arch/common.h
Original file line number Diff line number Diff line change
Expand Up @@ -94,6 +94,11 @@ struct queue_end_s {
#include "fas_arch/arduino_rp_pico.h"
#include "pd_pico/pd_config.h"

#elif defined(ARDUINO_ARCH_STM32)
// STM32 family (STM32duino core)
#include "fas_arch/arduino_stm32.h"
#include "pd_stm32/pd_config.h"

#else
#error "Unsupported devices"
#endif
Expand Down
2 changes: 2 additions & 0 deletions src/fas_queue/stepper_queue.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,8 @@
#include "pd_pico/pico_queue.h"
#elif defined(SUPPORT_ESP32)
#include "pd_esp32/esp32_queue.h"
#elif defined(FAS_STM32)
#include "pd_stm32/stm32_queue.h"
#else
#error "Unsupported architecture"
#endif
Expand Down
91 changes: 91 additions & 0 deletions src/fas_ramp/RampCalculator.h
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,97 @@
#define LOG2_ACCEL_FACTOR LOG2_CONST_2205E11
#define US_TO_TICKS(u32) ((u32) * 21)
#define TICKS_TO_US(u32) ((u32) / 21)
#elif (TICKS_PER_S == 32000000L)
// STM32L0, RP2040
#define LOG2_TICKS_PER_S ((log2_value_t)0x31dd)
#define LOG2_TICKS_PER_S_DIV_SQRT_OF_2 ((log2_value_t)0x30dd)
#define LOG2_ACCEL_FACTOR ((log2_value_t)0x61ba)
#define US_TO_TICKS(u32) ((u32) * 32)
#define TICKS_TO_US(u32) ((u32) / 32)
#elif (TICKS_PER_S == 48000000L)
// STM32F0/G0/WL
#define LOG2_TICKS_PER_S ((log2_value_t)0x3308)
#define LOG2_TICKS_PER_S_DIV_SQRT_OF_2 ((log2_value_t)0x3208)
#define LOG2_ACCEL_FACTOR ((log2_value_t)0x6411)
#define US_TO_TICKS(u32) ((u32) * 48)
#define TICKS_TO_US(u32) ((u32) / 48)
#elif (TICKS_PER_S == 64000000L)
// STM32G0/WB
#define LOG2_TICKS_PER_S ((log2_value_t)0x33dd)
#define LOG2_TICKS_PER_S_DIV_SQRT_OF_2 ((log2_value_t)0x32dd)
#define LOG2_ACCEL_FACTOR ((log2_value_t)0x65ba)
#define US_TO_TICKS(u32) ((u32) * 64)
#define TICKS_TO_US(u32) ((u32) / 64)
#elif (TICKS_PER_S == 72000000L)
// STM32F1/L1 (most common)
#define LOG2_TICKS_PER_S ((log2_value_t)0x3434)
#define LOG2_TICKS_PER_S_DIV_SQRT_OF_2 ((log2_value_t)0x3334)
#define LOG2_ACCEL_FACTOR ((log2_value_t)0x6668)
#define US_TO_TICKS(u32) ((u32) * 72)
#define TICKS_TO_US(u32) ((u32) / 72)
#elif (TICKS_PER_S == 80000000L)
// STM32L4
#define LOG2_TICKS_PER_S ((log2_value_t)0x3482)
#define LOG2_TICKS_PER_S_DIV_SQRT_OF_2 ((log2_value_t)0x3382)
#define LOG2_ACCEL_FACTOR ((log2_value_t)0x6704)
#define US_TO_TICKS(u32) ((u32) * 80)
#define TICKS_TO_US(u32) ((u32) / 80)
#elif (TICKS_PER_S == 84000000L)
// STM32F401/411
#define LOG2_TICKS_PER_S ((log2_value_t)0x34a6)
#define LOG2_TICKS_PER_S_DIV_SQRT_OF_2 ((log2_value_t)0x33a6)
#define LOG2_ACCEL_FACTOR ((log2_value_t)0x674c)
#define US_TO_TICKS(u32) ((u32) * 84)
#define TICKS_TO_US(u32) ((u32) / 84)
#elif (TICKS_PER_S == 100000000L)
// STM32F411/746
#define LOG2_TICKS_PER_S ((log2_value_t)0x3527)
#define LOG2_TICKS_PER_S_DIV_SQRT_OF_2 ((log2_value_t)0x3427)
#define LOG2_ACCEL_FACTOR ((log2_value_t)0x684d)
#define US_TO_TICKS(u32) ((u32) * 100)
#define TICKS_TO_US(u32) ((u32) / 100)
#elif (TICKS_PER_S == 120000000L)
// STM32L4+/F4
#define LOG2_TICKS_PER_S ((log2_value_t)0x35ad)
#define LOG2_TICKS_PER_S_DIV_SQRT_OF_2 ((log2_value_t)0x34ad)
#define LOG2_ACCEL_FACTOR ((log2_value_t)0x695a)
#define US_TO_TICKS(u32) ((u32) * 120)
#define TICKS_TO_US(u32) ((u32) / 120)
#elif (TICKS_PER_S == 168000000L)
// STM32F405/407
#define LOG2_TICKS_PER_S ((log2_value_t)0x36a6)
#define LOG2_TICKS_PER_S_DIV_SQRT_OF_2 ((log2_value_t)0x35a6)
#define LOG2_ACCEL_FACTOR ((log2_value_t)0x6b4c)
#define US_TO_TICKS(u32) ((u32) * 168)
#define TICKS_TO_US(u32) ((u32) / 168)
#elif (TICKS_PER_S == 170000000L)
// STM32F3/G4
#define LOG2_TICKS_PER_S ((log2_value_t)0x36af)
#define LOG2_TICKS_PER_S_DIV_SQRT_OF_2 ((log2_value_t)0x35af)
#define LOG2_ACCEL_FACTOR ((log2_value_t)0x6b5e)
#define US_TO_TICKS(u32) ((u32) * 170)
#define TICKS_TO_US(u32) ((u32) / 170)
#elif (TICKS_PER_S == 216000000L)
// STM32F7
#define LOG2_TICKS_PER_S ((log2_value_t)0x375f)
#define LOG2_TICKS_PER_S_DIV_SQRT_OF_2 ((log2_value_t)0x365f)
#define LOG2_ACCEL_FACTOR ((log2_value_t)0x6cbe)
#define US_TO_TICKS(u32) ((u32) * 216)
#define TICKS_TO_US(u32) ((u32) / 216)
#elif (TICKS_PER_S == 480000000L)
// STM32H7 (default)
#define LOG2_TICKS_PER_S ((log2_value_t)0x39ad)
#define LOG2_TICKS_PER_S_DIV_SQRT_OF_2 ((log2_value_t)0x38ad)
#define LOG2_ACCEL_FACTOR ((log2_value_t)0x715a)
#define US_TO_TICKS(u32) ((u32) * 480)
#define TICKS_TO_US(u32) ((u32) / 480)
#elif (TICKS_PER_S == 550000000L)
// STM32H7 (overclock)
#define LOG2_TICKS_PER_S ((log2_value_t)0x3a12)
#define LOG2_TICKS_PER_S_DIV_SQRT_OF_2 ((log2_value_t)0x3912)
#define LOG2_ACCEL_FACTOR ((log2_value_t)0x7224)
#define US_TO_TICKS(u32) ((u32) * 550)
#define TICKS_TO_US(u32) ((u32) / 550)
#else
#define SUPPORT_LOG2_TIMER_FREQ_VARIABLES
#define LOG2_TICKS_PER_S log2_timer_freq
Expand Down
Loading
Loading