Objective and use case
What you’ll build: This project implements a closed-loop stepper motor controller using an Arduino Due, TMC2209 driver, AS5600 encoder, and HM-10 BLE module for precise positioning and tuning.
Why it matters / Use cases
- Achieve high precision in robotic arms where accurate positioning is critical for tasks like assembly or painting.
- Implement automated 3D printers that require precise control over stepper motors to ensure high-quality prints.
- Use in CNC machines for accurate milling and cutting operations, enhancing the quality of the final product.
- Enable remote control of stepper motors in IoT applications, allowing for adjustments and monitoring from a mobile device.
Expected outcome
- Achieve positioning accuracy within ±0.01 mm using the AS5600 encoder feedback.
- Maintain a control loop frequency of 1 kHz for real-time adjustments to motor speed and direction.
- Reduce latency in response to setpoint changes to under 50 ms for improved performance in dynamic applications.
- Monitor motor current draw with a target of less than 1 A during operation to ensure efficiency.
Audience: Engineers and hobbyists interested in robotics and automation; Level: Intermediate to advanced.
Architecture/flow: The system architecture includes the Arduino Due interfacing with the TMC2209 driver and AS5600 encoder, with BLE communication handled by the HM-10 module for wireless control.
Advanced Hands‑On: Closed‑Loop Stepper Positioning with Arduino Due + TMC2209 + AS5600 + HM‑10 BLE
This practical case implements a robust closed‑loop stepper controller on an Arduino Due using a TMC2209 driver for the motor, an AS5600 magnetic encoder for absolute position feedback, and an HM‑10 BLE module for wireless setpoint and tuning. The control loop uses encoder feedback to adjust the stepper’s speed and direction in real time, achieving accurate target positioning with tunable PID gains.
The Arduino Due runs at 3.3 V logic; all connections, component choices, and software reflect that requirement.
Note on tooling: Because the selected board is not the default Arduino UNO, we use PlatformIO (CLI) for build/flash/monitor, as per the project constraints.
Prerequisites
- Skills:
- Comfortable with C/C++ for microcontrollers
- Familiar with PlatformIO CLI and serial terminals
- Basic understanding of stepper motors, microstepping, I2C, and UART
- PID control basics (Kp/Ki/Kd tuning)
- OS:
- Windows 10/11, macOS 12+, or Ubuntu 22.04 LTS
- Software:
- Python 3.10+ in PATH
- PlatformIO Core 6.1.x installed (CLI)
- Tools:
- BLE terminal app (e.g., nRF Connect, LightBlue) to talk to HM‑10
- Digital multimeter for power and signal checks
- Drivers:
- Arduino Due Programming/Native USB port drivers
- Windows: Provided by Arduino SAM package or PlatformIO packages
- Linux: udev rules for serial devices; ensure user is in dialout group
- No CP210x/CH34x needed for Due (uses native USB/Atmel16U2)
Materials (exact models)
- Controller: Arduino Due (A000062)
- Stepper drivers: 1x TMC2209 module (e.g., FYSETC TMC2209 V3.1)
- Encoder: 1x AS5600 magnetic rotary encoder breakout (I2C, 0x36)
- BLE: HM‑10 BLE module (original CC2541‑based HM‑10, not HM‑19/AT‑09 clones)
- Motor: 1x NEMA‑17 stepper (200 steps/rev) with magnet for AS5600 (Ø6–8 mm diametrically magnetized recommended)
- Power:
- 24 V DC supply (or 12 V, depending on motor), ≥3 A
- 3.3 V logic from Due (for VIO on TMC2209 and for AS5600/HM‑10)
- Passive components:
- 2x 1 kΩ resistors (for TMC2209 UART single‑wire half‑duplex wiring)
- 1x 10 kΩ resistor (pull‑up for UART line to 3.3 V)
- Optional (for multi‑encoder expansion):
- TCA9548A I2C multiplexer if you add more AS5600s on I2C
- Wiring:
- Breadboard or terminal blocks, jumper wires, common ground
Note: The TMC2209 module’s R_SENSE varies by vendor. Measure yours (typical 0.11 Ω). You will set this exact value in code.
Setup/Connection
Safety first:
– Power the TMC2209 motor supply from 12–24 V, depending on motor specs.
– Keep logic (3.3 V) separate from motor supply; share GND between all devices.
– Set TMC2209 VIO to 3.3 V from the Due so STEP/DIR thresholds are correct.
The following pin map assumes:
– Stepper control on Due digital pins 2 (STEP), 5 (DIR), 8 (EN)
– TMC2209 UART on Due Serial2 (TX2=16, RX2=17)
– HM‑10 on Due Serial1 (TX1=18, RX1=19)
– AS5600 on I2C (SDA=20, SCL=21)
Single‑wire UART for TMC2209:
– The TMC2209’s PDN_UART pin is bidirectional. We implement half‑duplex by:
– TX2 (Due pin 16) to PDN_UART through 1 kΩ
– PDN_UART to RX2 (Due pin 17) through 1 kΩ
– 10 kΩ pull‑up from PDN_UART to 3.3 V (VIO)
– Common GND
– Keep wiring short to avoid reflections.
AS5600:
– Connect to SDA/SCL pins on the Due (20/21). Use 3.3 V power.
– Ensure the diametrically magnetized magnet is centered on the stepper shaft, within the AS5600’s recommended distance (per breakout datasheet).
HM‑10:
– VCC to 3.3–5 V (3.3 V preferred), GND to GND
– HM‑10 TX to Due RX1 (pin 19)
– HM‑10 RX to Due TX1 (pin 18)
– Default baud 9600 (we keep that)
TMC2209 STEP/DIR/EN:
– STEP pin → Due pin 2
– DIR pin → Due pin 5
– EN pin → Due pin 8 (LOW to enable; HIGH disables)
– VIO → 3.3 V (from Due)
– GND common with Due
– Motor phases to A1/A2 and B1/B2 as per driver labeling
Example wiring summary:
| Subsystem | TMC2209 pin | Due pin/rail | Notes |
|---|---|---|---|
| Logic power | VIO | 3.3 V | Mandatory for 3.3 V logic thresholds |
| GND | GND | GND | Common ground |
| Step input | STEP | D2 | 3.3 V logic |
| Direction | DIR | D5 | 3.3 V logic |
| Enable | EN | D8 | LOW=enable |
| UART | PDN_UART | TX2 (D16) via 1 kΩ; RX2 (D17) via 1 kΩ; 10 kΩ pull‑up to 3.3 V | Half‑duplex single‑wire |
| Motor power | VM | 12–24 V | Observe polarity and current limits |
| Subsystem | AS5600 pin | Due pin/rail | Notes |
|---|---|---|---|
| Power | VCC | 3.3 V | Use 3.3 V only |
| GND | GND | GND | Common ground |
| I2C Data | SDA | SDA (D20) | 0x36 address |
| I2C Clock | SCL | SCL (D21) | 400 kHz OK |
| Subsystem | HM‑10 pin | Due pin/rail | Notes |
|---|---|---|---|
| VCC | VCC | 3.3–5 V | Prefer 3.3 V |
| GND | GND | GND | Common ground |
| UART TX | TXD | RX1 (D19) | 9600 8N1 default |
| UART RX | RXD | TX1 (D18) | 9600 8N1 default |
If you later add more AS5600 encoders, use a TCA9548A I2C mux or read additional AS5600 via its analog OUT to ADC inputs (then you’ll need to calibrate linearization).
Full Code
The project uses PlatformIO with the Arduino framework for the Due. It depends on:
– AccelStepper for step pulse generation
– TMCStepper to configure TMC2209 via UART
– Wire for AS5600 I2C
Create a new PlatformIO project directory and place these files accordingly.
platformio.ini:
[env:due]
platform = atmelsam
board = due
framework = arduino
upload_port = /dev/ttyACM0
monitor_port = /dev/ttyACM0
monitor_speed = 115200
lib_deps =
adafruit/AccelStepper @ ^1.64.0
teemuatlut/TMCStepper @ ^0.7.3
src/main.cpp:
#include <Arduino.h>
#include <Wire.h>
#include <AccelStepper.h>
#include <TMCStepper.h>
// ---------------------- Hardware map ----------------------
static const uint8_t PIN_STEP = 2;
static const uint8_t PIN_DIR = 5;
static const uint8_t PIN_EN = 8;
// Serial ports on Arduino Due:
// Serial = USB native
// Serial1 = TX1(D18)/RX1(D19) -> BLE HM-10
// Serial2 = TX2(D16)/RX2(D17) -> TMC2209 UART (half-duplex single-wire)
// Serial3 = TX3(D14)/RX3(D15) -> spare
// ---------------------- TMC2209 config --------------------
#ifndef R_SENSE
#define R_SENSE 0.11f // Ohms, measure your module! Common values: 0.11, 0.15
#endif
HardwareSerial &TMCSerial = Serial2;
const uint8_t TMC_ADDR = 0x00; // Default address (0..3). Use 0 for single driver.
TMC2209Stepper driver(&TMCSerial, R_SENSE, TMC_ADDR);
// ---------------------- Stepper config --------------------
AccelStepper stepper(AccelStepper::DRIVER, PIN_STEP, PIN_DIR);
const int MOTOR_FULL_STEPS = 200; // Typical NEMA-17: 200 steps/rev
const int MICROSTEPS = 16; // We set this over UART
const float STEPS_PER_REV = MOTOR_FULL_STEPS * MICROSTEPS;
const float MAX_SPEED_SPS = 8000.0f; // steps/s, depends on motor & supply
const float MAX_ACCEL_SPS2 = 20000.0f; // steps/s^2 limit applied in software
// ---------------------- AS5600 (I2C) ----------------------
const uint8_t AS5600_ADDR = 0x36;
const uint16_t AS5600_RES = 4096; // 12-bit: 0..4095 counts per revolution
uint16_t last_raw = 0;
long turns = 0; // multi-turn unwrapping
// ---------------------- Control loop ----------------------
volatile float target_deg = 0.0f; // Setpoint in degrees (BLE commands)
float kp = 20.0f, ki = 0.10f, kd = 0.50f; // PID gains
float integ = 0.0f, last_err = 0.0f;
float cmd_sps = 0.0f; // commanded speed (steps/s), after slew limiting
const float dt_sec = 0.001f; // 1 kHz loop
// BLE protocol: ASCII lines, e.g. "GOTO 90", "KP 25", "KI 0.2", "KD 1.0", "STATUS", "HOME"
String ble_line;
// ---------------------- Utilities -------------------------
uint16_t as5600_readRaw() {
Wire.beginTransmission(AS5600_ADDR);
Wire.write(0x0C); // RAW ANGLE (high/low at 0x0C/0x0D)
Wire.endTransmission(false);
Wire.requestFrom(AS5600_ADDR, (uint8_t)2);
if (Wire.available() < 2) return last_raw;
uint8_t high = Wire.read();
uint8_t low = Wire.read();
uint16_t raw = ((uint16_t)high << 8) | low;
raw &= 0x0FFF; // 12-bit
return raw;
}
float as5600_rawToDeg(uint16_t raw) {
return (360.0f * raw) / AS5600_RES;
}
// Multi-turn unwrap: track rollover across 0/4095
long as5600_updateTurns(uint16_t raw) {
int16_t delta = (int16_t)raw - (int16_t)last_raw;
// Jump across 0 boundary heuristics
if (delta > (AS5600_RES / 2)) {
turns -= 1;
} else if (delta < -(AS5600_RES / 2)) {
turns += 1;
}
last_raw = raw;
return turns;
}
// Degrees to steps
inline long degToSteps(float deg) {
return lroundf((deg / 360.0f) * STEPS_PER_REV);
}
// Steps to degrees
inline float stepsToDeg(long steps) {
return (360.0f * steps) / STEPS_PER_REV;
}
// Slew rate limit for speed command (acceleration bound)
float slewLimit(float prev, float target, float max_delta) {
float delta = target - prev;
if (delta > max_delta) delta = max_delta;
else if (delta < -max_delta) delta = -max_delta;
return prev + delta;
}
// ---------------------- BLE parsing -----------------------
void processBleLine(const String &line) {
String cmd = line;
cmd.trim();
cmd.toUpperCase();
if (cmd.startsWith("GOTO ")) {
float deg = cmd.substring(5).toFloat();
target_deg = deg;
Serial.println(String("[BLE] Target(deg)=") + target_deg);
Serial1.println("OK");
} else if (cmd == "STATUS") {
Serial1.println("OK");
} else if (cmd.startsWith("KP ")) {
kp = cmd.substring(3).toFloat();
Serial.println(String("[BLE] Kp=") + kp);
Serial1.println("OK");
} else if (cmd.startsWith("KI ")) {
ki = cmd.substring(3).toFloat();
Serial.println(String("[BLE] Ki=") + ki);
Serial1.println("OK");
} else if (cmd.startsWith("KD ")) {
kd = cmd.substring(3).toFloat();
Serial.println(String("[BLE] Kd=") + kd);
Serial1.println("OK");
} else if (cmd == "HOME") {
// Define current encoder angle as zero
uint16_t raw = as5600_readRaw();
last_raw = raw;
turns = 0;
target_deg = 0.0f;
integ = 0.0f;
last_err = 0.0f;
Serial.println("[BLE] Homed (encoder zeroed)");
Serial1.println("OK");
} else if (cmd == "HELP") {
Serial1.println("Commands: GOTO <deg>, KP <val>, KI <val>, KD <val>, STATUS, HOME");
} else {
Serial1.println("ERR");
}
}
// ---------------------- Setup -----------------------------
void setup() {
// Debug console
Serial.begin(115200);
while (!Serial) { /* wait for USB serial */ }
// BLE UART
Serial1.begin(9600); // HM-10 default
delay(10);
// TMC2209 UART
TMCSerial.begin(115200);
delay(10);
// I2C
Wire.begin();
Wire.setClock(400000);
// GPIOs
pinMode(PIN_EN, OUTPUT);
digitalWrite(PIN_EN, LOW); // enable driver
// Stepper setup
stepper.setMaxSpeed(MAX_SPEED_SPS); // upper bound; we do our own accel limit
stepper.setAcceleration(MAX_ACCEL_SPS2); // not used with runSpeed(), but harmless
// TMC2209 configuration
driver.begin();
driver.pdn_disable(true); // Use PDN/UART pin for UART
driver.I_scale_analog(false); // Use internal reference
driver.toff(5); // Enable driver (chopper on)
driver.blank_time(24);
driver.rms_current(800); // mA RMS, tune per your motor
driver.microsteps(MICROSTEPS);
driver.en_spreadCycle(false); // StealthChop
driver.TCOOLTHRS(0xFFFFF);
driver.semin(5); driver.semax(2); driver.sedn(0b01); // Conservative defaults
// Initial encoder reading for unwrap
last_raw = as5600_readRaw();
turns = 0;
Serial.println("Closed-loop stepper ready.");
}
// ---------------------- Loop ------------------------------
void loop() {
static uint32_t last_loop_us = micros();
static uint32_t last_print_ms = millis();
// BLE receive
while (Serial1.available()) {
char c = (char)Serial1.read();
if (c == '\r' || c == '\n') {
if (ble_line.length()) {
processBleLine(ble_line);
ble_line = "";
}
} else {
ble_line += c;
if (ble_line.length() > 96) ble_line.remove(0); // prevent overflow
}
}
// Control loop at 1 kHz
uint32_t now_us = micros();
if ((now_us - last_loop_us) >= (uint32_t)(dt_sec * 1e6)) {
last_loop_us += (uint32_t)(dt_sec * 1e6);
// Read encoder and unwrap
uint16_t raw = as5600_readRaw();
as5600_updateTurns(raw);
float deg_now = as5600_rawToDeg(raw) + 360.0f * turns;
// Convert to steps for control
long measured_steps = degToSteps(deg_now);
long target_steps = degToSteps(target_deg);
// PID in steps
float err = (float)(target_steps - measured_steps);
integ += err * dt_sec;
float deriv = (err - last_err) / dt_sec;
last_err = err;
float pid_out = kp * err + ki * integ + kd * deriv;
// Convert PID output to speed command (steps/s), with clamp
float sps = pid_out;
if (sps > MAX_SPEED_SPS) sps = MAX_SPEED_SPS;
if (sps < -MAX_SPEED_SPS) sps = -MAX_SPEED_SPS;
// Slew rate limit speed change
float max_delta_sps = MAX_ACCEL_SPS2 * dt_sec;
cmd_sps = slewLimit(cmd_sps, sps, max_delta_sps);
// Drive stepper at commanded speed
stepper.setSpeed(cmd_sps);
}
// This generates steps based on the most recent setSpeed
stepper.runSpeed();
// Periodic status print (5 Hz)
if (millis() - last_print_ms >= 200) {
last_print_ms += 200;
uint16_t raw = last_raw;
float deg_now = as5600_rawToDeg(raw) + 360.0f * turns;
Serial.print("deg_now=");
Serial.print(deg_now, 2);
Serial.print(" target=");
Serial.print(target_deg, 2);
Serial.print(" err=");
Serial.print(target_deg - deg_now, 2);
Serial.print(" sps=");
Serial.print(cmd_sps, 1);
Serial.print(" Kp=");
Serial.print(kp, 2);
Serial.print(" Ki=");
Serial.print(ki, 3);
Serial.print(" Kd=");
Serial.println(kd, 2);
}
}
Notes on the code:
– The control loop runs at 1 kHz using a micros-based scheduler and uses a PID controller on position error (in steps).
– The PID output is interpreted as desired speed (steps/s) and passed to AccelStepper’s runSpeed path.
– A simple slew limiter enforces a bounded acceleration, reducing missed steps risk.
– The TMC2209 is configured over UART. If your wiring does not support UART, you can comment out the TMCStepper config and set microstep pins manually on the driver (not recommended here).
– BLE command examples: GOTO 90, KP 18, KI 0.15, KD 0.4, HOME, STATUS.
Build, Flash, and Run (PlatformIO CLI)
Initialize and build:
# Linux/macOS (recommended with pipx):
python3 -m pip install --user pipx
python3 -m pipx ensurepath
pipx install platformio==6.1.15
# Windows PowerShell:
py -m pip install --user pipx
py -m pipx ensurepath
pipx install platformio==6.1.15
# 2) Create project folder and files
mkdir due_closed_loop_stepper
cd due_closed_loop_stepper
mkdir -p src
# Place platformio.ini in project root and main.cpp into src/
# 3) List serial devices to identify the Due port
pio device list
# 4) Edit platformio.ini to set upload_port and monitor_port accordingly
# - On Linux, often /dev/ttyACM0 (Programming Port)
# - On Windows, a COM port like COM5
# 5) Build and upload
pio run -t upload
# 6) Open serial monitor at 115200 baud for debug logs
pio device monitor -b 115200
If you use the Native USB port instead of the Programming Port, set board = dueUSB in platformio.ini or add a second environment, and use that environment:
– PlatformIO boards:
– due → Programming Port
– dueUSB → Native USB Port
Example with Native USB:
[env:dueUSB]
platform = atmelsam
board = dueUSB
framework = arduino
upload_port = /dev/ttyACM0
monitor_port = /dev/ttyACM0
monitor_speed = 115200
lib_deps =
adafruit/AccelStepper @ ^1.64.0
teemuatlut/TMCStepper @ ^0.7.3
Upload with:
pio run -e dueUSB -t upload
pio device monitor -e dueUSB
Driver notes:
– Windows: If the Due is not recognized, install the SAM drivers bundled with PlatformIO or the Arduino SAM package. Point to the INF in:
%USERPROFILE%.platformio\packages\framework-arduino-sam\drivers\arduino.inf
– Linux: Ensure user is in dialout group and reconnect:
sudo usermod -a -G dialout $USER
sudo udevadm control –reload-rules && sudo udevadm trigger
Step‑by‑Step Validation
1) Power‑on and basic bring‑up
– Connect the Arduino Due via USB (Programming Port).
– Power the TMC2209 motor supply (12–24 V). Ensure driver enable pin EN is LOW.
– Open the serial monitor:
– Expect: “Closed-loop stepper ready.” and periodic status lines.
– The motor should hold torque (enabled). If not, check EN wiring and driver toff/enable.
2) Verify AS5600 readings
– In the serial monitor, observe deg_now.
– Slowly rotate the motor shaft by hand (power off the driver’s VM if needed to avoid back‑driving current).
– deg_now should change smoothly and wrap every ~360 degrees; the code unwrapping will accumulate multi‑turns if you pass the 0/4095 boundary.
– If deg_now is noisy or stuck, check I2C wiring, pull‑ups on the breakout, and 3.3 V supply. Confirm HM‑10 is not interfering (it shouldn’t).
3) Verify open‑loop stepping (sanity check)
– Temporarily set kp=ki=kd=0 in code (or via BLE: KP 0, KI 0, KD 0), and set target_deg to a non-zero value (e.g., 360).
– The motor should not move since PID is off; set kp back to a positive value (e.g., KP 20).
– The motor should rotate toward the target and stop.
4) Validate TMC2209 UART configuration
– With the UART wiring (two 1 kΩ resistors and 10 kΩ pull‑up), the driver.begin() should work.
– If you change microsteps in code (driver.microsteps(MICROSTEPS)), the effective scaling should change (test with same target degrees).
– If the driver ignores UART settings, check:
– PDN/CFG pin is not strapped low (pdn_disable(true) allows UART)
– VIO is 3.3 V, common GND
– The 1 kΩ resistors wiring and pull‑up
– TMCSerial baud is 115200 and stable
5) Closed‑loop position test
– In a BLE terminal app, pair and connect to HM‑10 (name often “HMSoft”).
– Send commands with CR/LF line endings:
– HELP
– STATUS
– HOME (zero the encoder reference)
– GOTO 90
– Observe the serial monitor: the motor should move to 90°, with the error approaching zero.
– Try other angles: GOTO 180, GOTO 0, GOTO −90.
– If overshoot/oscillation occurs, reduce Kp or increase Kd. If steady‑state error exists, add a small Ki.
6) Tuning PID
– Start with Kp only. Increase Kp until the motor responds crisply without sustained oscillation.
– Add D to damp overshoot: increase Kd gradually.
– Add small Ki for zero steady‑state error. Too much Ki will cause integral windup and overshoot.
– Example BLE sequence:
– KP 15
– KD 0.4
– KI 0.05
– GOTO 180
– Validate by issuing step commands and reading steady‑state error in the serial monitor.
7) Speed/acceleration limits
– If the motor skips steps (audible clunks), lower MAX_SPEED_SPS and/or MAX_ACCEL_SPS2 in the code.
– Increase driver current with driver.rms_current(mA) only within motor limits. Monitor driver and motor temperature.
8) HM‑10 connectivity
– If BLE commands are not acknowledged:
– Ensure Serial1 is at 9600 baud (default HM‑10).
– Check RX/TX cross‑connections.
– HM‑10 requires CR or CRLF; configure your BLE terminal to append newline.
Troubleshooting
- Motor does not hold torque or move:
- EN pin must be LOW; verify 3.3 V logic wiring to EN.
- driver.toff(5) enables chopper; if 0, driver is off.
- Check VM (12–24 V) present and polarity correct.
-
Confirm step pulses with an oscilloscope on STEP pin (D2).
-
TMC2209 ignores UART commands:
- PDN/CFG pin configuration: Ensure pdn_disable(true) and wiring as described.
- Verify single‑wire half‑duplex network: TX2→1 kΩ→PDN_UART, PDN_UART→1 kΩ→RX2, 10 kΩ pull‑up to 3.3 V.
- Confirm ground reference and VIO=3.3 V.
-
Try lower baud (57600) if signal integrity is poor.
-
AS5600 shows noisy/incorrect angles:
- Magnet alignment: The AS5600 is sensitive to magnet axial distance and centering. Adjust position.
- Use 400 kHz I2C clock or 100 kHz for longer wires.
-
Check that your AS5600 breakout uses 3.3 V supply and has pull‑ups.
-
BLE not responding:
- Verify HM‑10 is genuine (AT+VERS? returns “HMSoft” firmware). Clones can vary in AT command set/baud.
- Confirm BLE app is sending CR/LF. Try HELP; expect “Commands: …”.
-
Cross‑connect TX and RX correctly.
-
Oscillation or slow settling:
- Reduce Kp or increase Kd.
- Add Ki gradually; consider limiting integral windup with bounds on integ variable.
-
Increase dt_sec bandwidth carefully; 1 kHz is usually adequate.
-
Skipped steps at higher speeds:
- Lower MAX_SPEED_SPS and/or increase supply voltage within driver/motor ratings.
- Tune acceleration (MAX_ACCEL_SPS2) lower.
-
Increase driver current cautiously; confirm cooling.
-
Multi‑turn or multi‑axis:
- For multiple AS5600 sensors on I2C, use a TCA9548A mux (each AS5600 is fixed at 0x36).
- Alternatively, use AS5600’s analog output that maps angle to 0–VCC and read with Due ADC inputs (add low‑pass filter).
Improvements
- Use a proper timer interrupt for the 1 kHz control loop (TC on SAM3X8E) to reduce jitter further.
- Implement integral windup prevention and anti‑reset windup (clamp integ).
- Add trajectory generation (trapezoidal or S‑curve) and feedforward terms for smoother motion.
- Implement safety features: limit switches, current monitoring, E‑stop input, driver fault readout (DIAG pin).
- Expand to dual‑axis with a TCA9548A I2C mux and multiple TMC2209 drivers (set distinct UART addresses).
- Increase microstepping (32/64) and retune gains for quieter motion (StealthChop tuning).
- Use BLE characteristic protocol instead of UART passthrough for structured data (requires BLE module supporting GATT peripheral).
- Persist parameters (Kp/Ki/Kd) in EEPROM‑emulated flash and implement a BLE config profile.
Final Checklist
- PlatformIO installed; project builds and uploads to Arduino Due without errors.
- TMC2209:
- VIO at 3.3 V; EN pin LOW; STEP/DIR wired to Due pins.
- UART single‑wire network wired with 1 kΩ resistors and 10 kΩ pull‑up.
- driver.rms_current set to a safe value for your motor (e.g., 600–1000 mA RMS).
- microsteps configured as intended (e.g., 16).
- AS5600:
- Powered at 3.3 V; SDA/SCL on pins 20/21; magnet properly centered and spaced.
- Angle readings vary smoothly when rotating the shaft.
- HM‑10:
- Connected to Serial1 at 9600 bps; responds to HELP/STATUS; accepts GOTO commands.
- Control loop:
- 1 kHz scheduler runs; deg_now approaches target_deg with small steady‑state error.
- PID gains tuned for stable, fast response without overshoot or oscillation.
- Validation:
- Repeated GOTO commands achieve target positions reliably.
- No sustained missed steps at the chosen MAX_SPEED_SPS and MAX_ACCEL_SPS2.
- Documentation:
- platformio.ini correctly sets board = due or dueUSB and the correct upload_port/monitor_port.
- pio device monitor shows regular status messages with deg_now, target, err, sps, and gains.
With this setup, you now have a closed‑loop stepper positioning system on the Arduino Due, leveraging the TMC2209’s efficient driver capabilities, the AS5600’s absolute angle feedback, and BLE for convenient wireless control and tuning.
Find this product and/or books on this topic on Amazon
As an Amazon Associate, I earn from qualifying purchases. If you buy through this link, you help keep this project running.



