Practical case: ESP32 PID DC motor control, AS5600, TB6612

Practical case: ESP32 PID DC motor control, AS5600, TB6612 — hero

Objective and use case

What you’ll build: Implement a closed-loop PID controller that regulates the velocity of a DC motor using an AS5600 magnetic encoder for feedback, driven by a TB6612FNG H-bridge, all controlled by an ESP32 DevKitC.

Why it matters / Use cases

  • Automated robotics: Precise control of motor speed for robotic arms or mobile robots to enhance movement accuracy.
  • 3D printers: Maintaining consistent motor velocity for improved print quality and reduced layer misalignment.
  • Conveyor systems: Ensuring uniform speed in material handling systems to optimize production efficiency.
  • Electric vehicles: Fine-tuning motor response for better handling and energy efficiency in electric drive systems.

Expected outcome

  • Achieve a motor speed regulation accuracy within ±5 RPM.
  • Latency in control response under 50 ms for real-time adjustments.
  • Maintain a stable control loop with less than 10% overshoot during speed changes.
  • Monitor and report motor performance metrics such as speed (RPM), current (A), and temperature (°C) for diagnostics.

Audience: Advanced users familiar with embedded systems; Level: Advanced

Architecture/flow: ESP32 DevKitC processes encoder feedback from AS5600 and adjusts motor speed via TB6612FNG based on PID control logic.

Advanced Practical: PID Velocity Control of a DC Motor using ESP32 DevKitC + TB6612FNG + AS5600

Goal: Implement a closed-loop PID controller that regulates DC motor shaft velocity using a magnetic encoder (AS5600) as feedback and drives the motor via the TB6612FNG H‑bridge. The controller runs on an ESP32 DevKitC, with a reproducible build using PlatformIO.

Focus: pid-dc-motor-encoder-velocity

Exact device model: ESP32 DevKitC + TB6612FNG + AS5600


Prerequisites

  • Skill level: Advanced (comfortable with embedded C/C++, control theory basics, and I2C)
  • Development environment:
  • PlatformIO Core (CLI) 6.x installed via pip or the PlatformIO installer
  • Python 3.8+ on your host machine
  • A serial terminal (PlatformIO’s built-in monitor is used below)
  • ESP32 USB-UART driver:
  • ESP32 DevKitC commonly uses Silicon Labs CP2102N
    • Windows: Install “CP210x Universal Windows Driver”
    • macOS: Modern versions typically do not require a driver; if needed, install CP210x VCP driver
    • Linux: The cp210x kernel module is usually present; verify with dmesg after plugging in
  • Clones may use WCH CH340; if so, install the CH34x driver instead

Materials (with exact model)

  • 1x ESP32 DevKitC (official Espressif DevKitC)
  • 1x TB6612FNG dual H‑bridge breakout (logic 3.3–5 V compatible)
  • 1x AS5600 magnetic rotary position sensor breakout (I2C mode, 3.3–5 V supply)
  • 1x DC motor with shaft magnet for AS5600 (use a diametrically magnetized magnet per AS5600 datasheet)
  • Power supply for motor (VM): e.g., 6–12 V DC with current rating exceeding motor stall current
  • Breadboard and wires
  • Common ground between ESP32 and motor driver power
  • Optional: 100 nF ceramic decoupling caps near AS5600 and TB6612FNG VCC pins, bulk cap (e.g., 220 µF) at motor supply

Setup / Connection

  • Logic power: TB6612FNG VCC at 3.3 V from ESP32; AS5600 at 3.3 V (recommended)
  • Motor power: TB6612FNG VM from your motor PSU (e.g., 9 V). Grounds must be common
  • I2C: AS5600 default I2C address is 0x36, use 400 kHz bus for faster sampling

Recommended ESP32 pin assignments:

  • I2C: SDA = GPIO21, SCL = GPIO22 (ESP32 DevKitC default)
  • TB6612FNG (single channel, A-side):
  • PWMA (PWM) -> GPIO25 (LEDC)
  • AIN1 (direction) -> GPIO26
  • AIN2 (direction) -> GPIO27
  • STBY (standby enable) -> GPIO14 (set HIGH to enable driver)
  • AO1/AO2 -> Motor terminals
  • VCC -> 3.3 V; VM -> Motor PSU; GND -> Common
  • AS5600:
  • VCC -> 3.3 V
  • GND -> GND
  • SDA -> GPIO21
  • SCL -> GPIO22

Notes:
– Avoid ESP32 input-only pins (GPIO 34–39) for outputs.
– Avoid boot strapping pins for control lines that change at boot (GPIO 0, 2, 15) unless you understand the implications.
– TB6612FNG supports high PWM frequency (e.g., 20 kHz) to reduce audible noise.

Connection Table

Module/Signal Pin on Module Pin on ESP32 DevKitC Notes
TB6612FNG Logic VCC VCC 3.3 V Logic supply (2.7–5.5 V). Use 3.3 V
TB6612FNG Standby STBY GPIO14 Drive HIGH to enable driver
TB6612FNG A PWM PWMA GPIO25 LEDC PWM, 20 kHz recommended
TB6612FNG A Dir1 AIN1 GPIO26 Motor direction
TB6612FNG A Dir2 AIN2 GPIO27 Motor direction
TB6612FNG Motor Power VM Motor PSU + 6–12 V typical; not from ESP32
TB6612FNG Ground GND GND Common ground with ESP32
TB6612FNG Motor Out AO1/AO2 Motor Connect both motor leads
AS5600 Power VCC 3.3 V Power for sensor
AS5600 Ground GND GND Common ground
AS5600 SDA SDA GPIO21 I2C data
AS5600 SCL SCL GPIO22 I2C clock

Mechanical:
– Mount the AS5600 module coaxially with the motor shaft; keep gap ~1–3 mm depending on magnet and module.
– Use a diametrically magnetized magnet on the shaft; ensure centered alignment for best signal.


Full Code

This project uses an Arduino-based PlatformIO environment. The controller runs a 500 Hz loop in a FreeRTOS task, reads angle from AS5600 (I2C 0x36), computes velocity via angle unwrapping, and applies a PID to regulate the speed using the TB6612FNG. A serial command interface lets you set the setpoint and PID gains and log data.

Place the following files in your PlatformIO project:

1) platformio.ini

; File: platformio.ini
; PlatformIO reproducible environment for ESP32 DevKitC + TB6612FNG + AS5600
[env:esp32devkitc]
platform = espressif32 @ 6.6.0
board = esp32dev
framework = arduino

monitor_speed = 115200
monitor_filters = time, colorize

; Optionally set upload port if auto-detection fails:
; upload_port = /dev/ttyUSB0
; upload_port = COM5

build_flags =
  -DCORE_DEBUG_LEVEL=2
  -Wall
  -Wextra

; No external libs needed; Wire comes with framework-arduinoespressif32

2) src/main.cpp

// File: src/main.cpp
#include <Arduino.h>
#include <Wire.h>

// ===================== Hardware Mapping ======================
static constexpr int PIN_I2C_SDA = 21;
static constexpr int PIN_I2C_SCL = 22;

// TB6612FNG (A-channel)
static constexpr int PIN_TB_STBY = 14;
static constexpr int PIN_TB_PWMA  = 25; // LEDC
static constexpr int PIN_TB_AIN1  = 26;
static constexpr int PIN_TB_AIN2  = 27;

// LEDC PWM
static constexpr int PWM_CH      = 0;
static constexpr int PWM_FREQ    = 20000;  // 20 kHz
static constexpr int PWM_RES_BITS = 12;    // 12-bit resolution
static constexpr int PWM_MAX      = (1 << PWM_RES_BITS) - 1;

// AS5600 (I2C address & registers)
static constexpr uint8_t AS5600_ADDR = 0x36;
static constexpr uint8_t AS5600_REG_RAW_ANGLE = 0x0C; // 12-bit raw angle
static constexpr float   AS5600_CPR = 4096.0f;
static constexpr float   TWO_PI = 6.283185307179586476925286766559f;

// Control loop
static constexpr float LOOP_HZ = 500.0f;      // 500 Hz control loop
static constexpr float TS = 1.0f / LOOP_HZ;   // 0.002 s

// Logging
static volatile uint32_t g_logDecim = 10; // Log at LOOP_HZ/g_logDecim (e.g., 50 Hz)

// ===================== State Variables =======================
static volatile bool g_run = false;
static volatile float g_setpoint_rps = 0.0f;   // setpoint in rotations per second
static volatile float g_kp = 0.08f;
static volatile float g_ki = 5.00f;
static volatile float g_kd = 0.000f;           // derivative term (on measurement), default off
static volatile float g_output_limit = 1.0f;   // command saturation [-1,1]
static volatile float g_integrator_limit = 0.75f;

// Angle/Velocity estimation
static float angle_prev = 0.0f;      // [rad], unwrapped incrementally
static float vel_rps = 0.0f;         // [rev/s]
static float vel_prev_rps = 0.0f;    // for derivative on measurement

// PID states
static float integrator = 0.0f;

// Task handle
static TaskHandle_t controlTaskHandle = nullptr;

// ===================== I2C Helpers ===========================
uint16_t as5600_readRawAngle() {
  Wire.beginTransmission(AS5600_ADDR);
  Wire.write(AS5600_REG_RAW_ANGLE);
  if (Wire.endTransmission(false) != 0) {
    return 0xFFFF; // signal error
  }
  int n = Wire.requestFrom(AS5600_ADDR, (uint8_t)2);
  if (n != 2) {
    return 0xFFFF;
  }
  uint8_t msb = Wire.read();
  uint8_t lsb = Wire.read();
  uint16_t raw = ((uint16_t)msb << 8) | lsb;
  raw &= 0x0FFF; // 12-bit
  return raw;
}

// Returns wrapped angle [rad] from raw counts
float as5600_readAngleRad() {
  uint16_t raw = as5600_readRawAngle();
  if (raw == 0xFFFF) {
    return NAN;
  }
  return (float)raw * (TWO_PI / AS5600_CPR);
}

// ===================== Motor Driver ==========================
void motor_init() {
  pinMode(PIN_TB_STBY, OUTPUT);
  pinMode(PIN_TB_AIN1, OUTPUT);
  pinMode(PIN_TB_AIN2, OUTPUT);
  digitalWrite(PIN_TB_STBY, HIGH); // enable

  ledcSetup(PWM_CH, PWM_FREQ, PWM_RES_BITS);
  ledcAttachPin(PIN_TB_PWMA, PWM_CH);
  ledcWrite(PWM_CH, 0);

  // default brake (coast)
  digitalWrite(PIN_TB_AIN1, LOW);
  digitalWrite(PIN_TB_AIN2, LOW);
}

void motor_command(float u) {
  // u in [-1, 1]
  if (u > g_output_limit) u = g_output_limit;
  if (u < -g_output_limit) u = -g_output_limit;

  bool forward = (u >= 0.0f);
  float mag = fabsf(u);

  uint32_t duty = (uint32_t)roundf(mag * PWM_MAX);
  if (duty > PWM_MAX) duty = PWM_MAX;

  if (mag < 1e-4f) {
    // Coast
    digitalWrite(PIN_TB_AIN1, LOW);
    digitalWrite(PIN_TB_AIN2, LOW);
    ledcWrite(PWM_CH, 0);
    return;
  }

  if (forward) {
    digitalWrite(PIN_TB_AIN1, HIGH);
    digitalWrite(PIN_TB_AIN2, LOW);
  } else {
    digitalWrite(PIN_TB_AIN1, LOW);
    digitalWrite(PIN_TB_AIN2, HIGH);
  }
  ledcWrite(PWM_CH, duty);
}

// ===================== Control Task ==========================
void controlLoop(void*) {
  TickType_t lastWake = xTaskGetTickCount();
  uint32_t loopCount = 0;

  // Initialize angle_prev with first reading
  float a0 = as5600_readAngleRad();
  while (isnan(a0)) {
    vTaskDelay(pdMS_TO_TICKS(10));
    a0 = as5600_readAngleRad();
  }
  angle_prev = a0;
  vel_prev_rps = 0.0f;

  for (;;) {
    vTaskDelayUntil(&lastWake, pdMS_TO_TICKS((int)(1000.0f / LOOP_HZ)));

    // 1) Read angle and compute velocity
    float a = as5600_readAngleRad();
    if (isnan(a)) {
      // Sensor read error: cut motor for safety
      motor_command(0.0f);
      continue;
    }
    float da = a - angle_prev;
    // unwrap across 0/2pi
    if (da > (TWO_PI * 0.5f)) da -= TWO_PI;
    else if (da < -(TWO_PI * 0.5f)) da += TWO_PI;

    // Convert to rotations per second
    float vel = (da / TWO_PI) / TS; // rev/s
    angle_prev = a;
    vel_rps = vel;

    // 2) PID control on velocity
    float sp = g_setpoint_rps;
    float e = sp - vel; // velocity error

    // Tustin integrator with anti-windup
    float integrator_candidate = integrator + 0.5f * g_ki * TS * (e + e); // since prev e not stored, approx Euler
    // Clamp integrator
    if (integrator_candidate > g_integrator_limit) integrator_candidate = g_integrator_limit;
    if (integrator_candidate < -g_integrator_limit) integrator_candidate = -g_integrator_limit;
    integrator = integrator_candidate;

    // Derivative on measurement (noise-robust)
    float dterm = 0.0f;
    if (g_kd != 0.0f) {
      float d_meas = (vel - vel_prev_rps) / TS;
      dterm = -g_kd * d_meas;
    }
    vel_prev_rps = vel;

    float u = g_kp * e + integrator + dterm;

    // 3) Apply command or cut if not running
    if (g_run) {
      motor_command(u);
    } else {
      motor_command(0.0f);
      integrator = 0.0f; // reset integrator when stopped
    }

    // 4) Logging
    if ((loopCount++ % g_logDecim) == 0) {
      // CSV: t_ms,sp_rps,vel_rps,cmd
      uint32_t t = millis();
      Serial.print("T,"); Serial.print(t);
      Serial.print(",SP,"); Serial.print(sp, 4);
      Serial.print(",VEL,"); Serial.print(vel_rps, 4);
      Serial.print(",U,"); Serial.print(u, 4);
      Serial.print(",E,"); Serial.print(e, 4);
      Serial.println();
    }
  }
}

// ===================== Command Parser ========================
static String inbuf;

void printHelp() {
  Serial.println(F("Commands:"));
  Serial.println(F("  RUN                -> enable control"));
  Serial.println(F("  STOP               -> disable control"));
  Serial.println(F("  SP <rpm>           -> set setpoint in RPM (can be negative)"));
  Serial.println(F("  SPRPS <rps>        -> set setpoint in RPS"));
  Serial.println(F("  KP <val>           -> set Kp"));
  Serial.println(F("  KI <val>           -> set Ki"));
  Serial.println(F("  KD <val>           -> set Kd (derivative on measurement)"));
  Serial.println(F("  LIM <u> <i>        -> set |U|max and |I|max (e.g., LIM 1.0 0.75)"));
  Serial.println(F("  LOG <hz>           -> log rate (<= loop rate), e.g., LOG 50"));
  Serial.println(F("  ?                  -> print current config"));
}

void printStatus() {
  Serial.print(F("RUN=")); Serial.print(g_run ? "1" : "0");
  Serial.print(F(" SP(RPS)=")); Serial.print(g_setpoint_rps, 4);
  Serial.print(F(" KP=")); Serial.print(g_kp, 4);
  Serial.print(F(" KI=")); Serial.print(g_ki, 4);
  Serial.print(F(" KD=")); Serial.print(g_kd, 6);
  Serial.print(F(" Ulim=")); Serial.print(g_output_limit, 3);
  Serial.print(F(" Imax=")); Serial.print(g_integrator_limit, 3);
  Serial.print(F(" LoopHz=")); Serial.print(LOOP_HZ);
  Serial.print(F(" LogHz=")); Serial.println(LOOP_HZ / (float)g_logDecim, 1);
}

void handleLine(const String& line) {
  if (line.length() == 0) return;
  String cmd = line;
  cmd.trim();
  cmd.toUpperCase();

  if (cmd == "RUN") {
    g_run = true;
    Serial.println(F("OK RUN"));
    return;
  }
  if (cmd == "STOP") {
    g_run = false;
    Serial.println(F("OK STOP"));
    return;
  }
  if (cmd == "?") {
    printStatus();
    return;
  }
  if (cmd.startsWith("SP ")) {
    float rpm = cmd.substring(3).toFloat();
    g_setpoint_rps = rpm / 60.0f;
    Serial.print(F("OK SP RPM=")); Serial.println(rpm, 3);
    return;
  }
  if (cmd.startsWith("SPRPS ")) {
    float rps = cmd.substring(6).toFloat();
    g_setpoint_rps = rps;
    Serial.print(F("OK SP RPS=")); Serial.println(rps, 4);
    return;
  }
  if (cmd.startsWith("KP ")) {
    g_kp = cmd.substring(3).toFloat();
    Serial.print(F("OK KP=")); Serial.println(g_kp, 6);
    return;
  }
  if (cmd.startsWith("KI ")) {
    g_ki = cmd.substring(3).toFloat();
    Serial.print(F("OK KI=")); Serial.println(g_ki, 6);
    return;
  }
  if (cmd.startsWith("KD ")) {
    g_kd = cmd.substring(3).toFloat();
    Serial.print(F("OK KD=")); Serial.println(g_kd, 6);
    return;
  }
  if (cmd.startsWith("LIM ")) {
    int s1 = cmd.indexOf(' ');
    int s2 = cmd.indexOf(' ', s1 + 1);
    if (s2 > 0) {
      g_output_limit = cmd.substring(s1 + 1, s2).toFloat();
      g_integrator_limit = cmd.substring(s2 + 1).toFloat();
      Serial.print(F("OK Ulim=")); Serial.print(g_output_limit, 3);
      Serial.print(F(" Imax=")); Serial.println(g_integrator_limit, 3);
      return;
    }
  }
  if (cmd.startsWith("LOG ")) {
    float hz = cmd.substring(4).toFloat();
    if (hz <= 0) hz = 1.0f;
    if (hz > LOOP_HZ) hz = LOOP_HZ;
    g_logDecim = (uint32_t)max(1.0f, roundf(LOOP_HZ / hz));
    Serial.print(F("OK LogHz=")); Serial.println(LOOP_HZ / (float)g_logDecim, 1);
    return;
  }

  Serial.println(F("ERR Unknown command"));
  printHelp();
}

void serialPoll() {
  while (Serial.available()) {
    char c = (char)Serial.read();
    if (c == '\r') continue;
    if (c == '\n') {
      handleLine(inbuf);
      inbuf = "";
    } else {
      inbuf += c;
      if (inbuf.length() > 120) inbuf = ""; // simple overflow guard
    }
  }
}

// ===================== Arduino Setup/Loop ====================
void setup() {
  Serial.begin(115200);
  delay(100);
  Serial.println(F("\nESP32 DevKitC + TB6612FNG + AS5600 - PID DC Motor Velocity"));

  Wire.begin(PIN_I2C_SDA, PIN_I2C_SCL, 400000); // 400 kHz
  delay(20);

  // Probe AS5600
  Wire.beginTransmission(AS5600_ADDR);
  if (Wire.endTransmission() != 0) {
    Serial.println(F("AS5600 not responding at 0x36. Check wiring and power."));
  } else {
    Serial.println(F("AS5600 detected at 0x36"));
  }

  motor_init();

  xTaskCreatePinnedToCore(controlLoop, "ctrl", 4096, nullptr, 2, &controlTaskHandle, 1);

  printHelp();
  printStatus();
}

void loop() {
  serialPoll();
  // Leave loop light; control is on its own task
}

Build / Flash / Run Commands

Execute these in a terminal within your project directory (where platformio.ini resides):

pio --version

# Initialize project (if not created yet); selects ESP32 DevKit environment
pio project init -b esp32dev

# Build firmware
pio run

# Flash to the board (auto-detects port; specify upload_port if needed)
pio run -t upload

# Open serial monitor at 115200 baud
pio device monitor -b 115200

Notes:
– If upload port is not detected, set upload_port in platformio.ini or pass --upload-port in the command:
– Example (Linux): pio run -t upload --upload-port /dev/ttyUSB0
– Example (Windows): pio run -t upload --upload-port COM5


Step‑by‑step Validation

This section validates velocity PID control against the AS5600 feedback. Keep fingers and loose items away from the spinning motor.

1) Pre-flight checks:
– Ensure common ground between ESP32, TB6612FNG, and AS5600.
– Confirm motor power supply is adequate and connected to VM on TB6612FNG.
– Open the serial monitor:
pio device monitor -b 115200
– On boot, you should see “AS5600 detected at 0x36”.

2) Sensor sanity check:
– With the motor unpowered (RUN not enabled), gently rotate the shaft by hand.
– Temporary diagnostic: enter RUN then STOP to verify driver readiness (should not spin when STOP).
– Add a logging command: LOG 20 to reduce output rate for readability.
– Enter SP 0 (default) to keep setpoint zero. Ensure VEL in logs is near zero when stationary, and changes sign when you rotate the shaft both ways.

3) Static offset and deadband test:
– Enter RUN with SP 10 (10 RPM ~ 0.1667 rps). Observe logs for SP and VEL.
– If the motor does not start due to static friction, increase Kp slightly:
KP 0.12 then KP 0.16 if needed (increment in small steps).
– If the motor overshoots wildly, reduce Kp or increase Ki damping (lower Ki).

4) Step response characterization:
– Start with conservative gains (default: KP=0.08, KI=5.0, KD=0.0). Set LOG 50.
– Enable control: RUN.
– Command a step: SP 60 (60 RPM = 1.0 rps).
– Observe the time to reach and stabilize near 1.0 rps, overshoot magnitude, and steady-state error.
– If steady-state error persists, increase Ki gradually (e.g., KI 6.0, KI 8.0).
– If oscillations occur, reduce Kp slightly (e.g., KP 0.07) or add small KD (e.g., KD 0.001).

5) Bidirectional test:
– While running at SP 60, change to SP -60. The motor should reverse smoothly and track approximately −1.0 rps.
– Evaluate reversal overshoot; if large, consider a small KD term.

6) Saturation and anti‑windup:
– Set a high setpoint near motor capability: SP 600 (600 RPM = 10 rps). You may see U saturating near 1.0.
– Drop to SP 0 abruptly. If the system brakes slowly or exhibits after-effect, reduce integrator limit: LIM 1.0 0.4.

7) Low-speed tracking:
– Test SP 5 RPM and SP 2 RPM. Low speeds are challenging due to friction and quantization.
– If the motor dithers, reduce Ki and consider reducing LOOP_HZ to 250 Hz (requires code change) or applying a minimum duty feedforward (see Improvements).

8) Log capture and quick analysis:
– In PlatformIO monitor, copy CSV-like log lines starting with T,.
– Paste into a spreadsheet and plot VEL vs SP over time to assess performance (rise time, overshoot, steady error).

9) Safety stop:
– Test STOP. Motor should coast (AIN1=AIN2=LOW, PWM=0).
– Resume with RUN and prior setpoint intact.

Expected results:
– At moderate speeds (e.g., 50–200 RPM), velocity tracking within a few percent with minimal overshoot after tuning.
– Stable bidirectional operation with no runaway or oscillation under nominal load.


Troubleshooting

  • AS5600 not detected:
  • Symptom: “AS5600 not responding at 0x36.”
  • Actions:

    • Verify VCC=3.3 V and GND.
    • Confirm SDA=GPIO21, SCL=GPIO22; check for swapped lines.
    • Ensure magnet is present only for measurement; detection does not depend on magnet.
    • Check pull-ups: most AS5600 boards have on-board pull-ups. If using a bare sensor, add 4.7 kΩ to 3.3 V on SDA/SCL.
    • Try a slower I2C speed: change Wire.begin third argument to 100000.
  • Motor does not spin when RUN and SP > 0:

  • Check TB6612FNG STBY is driven HIGH (GPIO14).
  • Ensure VM is connected to the motor PSU and is sufficient (check polarity).
  • Confirm AO1/AO2 wired to the motor terminals, not VCC pins.
  • Increase Kp slightly and test again; static friction may require more initial torque.

  • Motor spins only one direction or jerks:

  • Verify AIN1/AIN2 wiring and logic levels.
  • Ensure PWM pin is correctly attached to PWMA and LEDC channel is setup.
  • Remove conflicting uses of those GPIOs.

  • Unstable control or oscillations:

  • Lower Kp by small increments.
  • Decrease Ki to reduce integrator aggressiveness.
  • Add a small derivative on measurement (KD 0.0005–0.002) to dampen.

  • Noisy velocity measurement:

  • Reduce log rate (LOG 20) to focus.
  • Increase LOOP_HZ filter by implementing a low-pass on vel (see Improvements).
  • Ensure mechanical alignment of magnet; off-axis misalignment increases jitter.

  • Brownouts or resets:

  • The motor PSU may inject noise; add a bulk capacitor near TB6612FNG VM (e.g., 220–470 µF).
  • Keep motor and logic grounds well-connected but route high current away from sensor lines.
  • Use twisted pair for motor leads and keep AS5600 wiring short.

  • Upload issues (cannot connect to ESP32):

  • Hold BOOT button while initiating upload (if needed).
  • Select correct upload port in platformio.ini or command line.
  • Install CP210x or CH34x driver as applicable.

Improvements

  • Add velocity low-pass filtering:
  • Implement a first-order filter on vel_rps: vel_filt = alpha*vel + (1-alpha)*vel_filt_prev with alpha chosen based on bandwidth.
  • Add feedforward:
  • Estimate a simple static gain u_ff = kf * sp to reduce steady-state error; PID then corrects small residuals.
  • Rate limit the setpoint:
  • Avoid step changes beyond what the motor can track without saturating: ramp the setpoint (slew-rate limiter).
  • Advanced anti-windup:
  • Use back-calculation: integrator += (Ki * e + Kb * (u_sat - u_unsat)) * Ts.
  • Adaptive gains:
  • Increase Kp/Ki at higher speeds where friction is less dominant; reduce at low speeds.
  • Use a hardware timer or ESP-IDF esp_timer with dedicated I2C transaction scheduling for tighter loop timing.
  • Store tuned parameters in NVS (non-volatile storage) and add commands SAVE/LOAD.
  • Implement a more robust AS5600 read with retries and error counters.
  • Support both channels of TB6612FNG for two-motor control or differential drive.
  • Add a watchdog that disables the motor on sensor failure or communication timeout.

Final Checklist

  • Electrical:
  • ESP32 DevKitC powered via USB; driver installed (CP210x/CH34x as needed).
  • TB6612FNG: VCC=3.3 V, STBY tied to GPIO14 (HIGH), PWMA->GPIO25, AIN1->GPIO26, AIN2->GPIO27, VM to motor PSU, GND common.
  • AS5600: VCC=3.3 V, SDA->GPIO21, SCL->GPIO22, GND common.
  • Bulk capacitor on VM; clean wiring and short I2C lines.

  • Software:

  • PlatformIO environment created with board = esp32dev, platform = espressif32 @ 6.6.0.
  • Built and uploaded with pio run -t upload.
  • Serial monitor opened at 115200 baud.

  • Operation:

  • AS5600 detected at 0x36 on boot.
  • Control loop at 500 Hz; logging at 20–50 Hz as configured.
  • RUN, STOP, SP, KP, KI, KD, LIM, LOG, ? commands working.
  • Motor tracks setpoint in RPM/RPS with stable PID response after tuning.

  • Validation:

  • Step response tested at 60 RPM and −60 RPM; overshoot and settling acceptable.
  • High setpoint saturation behavior verified; anti-windup tuned.
  • Low-speed performance assessed; further improvements planned if needed.

With the ESP32 DevKitC + TB6612FNG + AS5600 integrated as above, you now have a reproducible, commandable, and tunable PID velocity controller for a DC motor that you can extend with filtering, feedforward, and adaptive strategies for production-grade performance.

Find this product and/or books on this topic on Amazon

Go to Amazon

As an Amazon Associate, I earn from qualifying purchases. If you buy through this link, you help keep this project running.

Quick Quiz

Question 1: What is the main goal of the project described in the article?




Question 2: Which microcontroller is used in this project?




Question 3: What type of sensor is the AS5600?




Question 4: What is the required skill level for this project?




Question 5: Which development environment is mentioned for the project?




Question 6: What type of driver is commonly used for the ESP32 DevKitC?




Question 7: What is the voltage supply range for the motor mentioned in the article?




Question 8: What is an optional component suggested for use near the AS5600?




Question 9: What type of motor driver is used in the project?




Question 10: What communication protocol does the AS5600 use?




Carlos Núñez Zorrilla
Carlos Núñez Zorrilla
Electronics & Computer Engineer

Telecommunications Electronics Engineer and Computer Engineer (official degrees in Spain).

Follow me:
error: Contenido Protegido / Content is protected !!
Scroll to Top