Practical case: ESP32 anomaly detection with I2S+MQTT

Practical case: ESP32 anomaly detection with I2S+MQTT — hero

Objective and use case

What you’ll build: This project implements real-time acoustic anomaly detection on an ESP32 using an I2S MEMS microphone (INMP441). Anomaly alerts are routed over MQTT, with visual status via a WS2812B LED and audible feedback through an I2S DAC/amplifier (MAX98357A).

Why it matters / Use cases

  • Real-time monitoring of industrial equipment for anomalies, reducing downtime and maintenance costs.
  • Smart home applications where audio feedback can alert users to unusual sounds, enhancing security.
  • Environmental monitoring systems that detect specific sound patterns indicative of wildlife or machinery.
  • Healthcare applications for monitoring patient environments, alerting staff to unusual sounds.

Expected outcome

  • Detection of anomalies with a latency of less than 100 ms.
  • MQTT alert messages sent within 200 ms of detection.
  • Visual feedback via WS2812B LED indicating status changes with a response time of 50 ms.
  • Audio feedback generated through MAX98357A with a response time of 100 ms.

Audience: Intermediate developers; Level: Advanced

Architecture/flow: ESP32 processes audio input from INMP441, analyzes it for anomalies, and communicates results via MQTT while providing visual and audio feedback.

ESP32 Advanced Practical: I2S Anomaly Detection with MQTT, Audio Beep, and LED Feedback

Objective: i2s-anomaly-detection-mqtt
Device family and exact model used: Espressif ESP32-DevKitC V4 (ESP32-WROOM-32) + INMP441 + MAX98357A + WS2812B

This advanced hands-on guide implements real-time acoustic anomaly detection on an ESP32 using an I2S MEMS microphone (INMP441), with anomaly alerts routed over MQTT, visual status via a WS2812B LED, and an audible beep generated through an I2S DAC/amplifier (MAX98357A). The project is reproducible with PlatformIO, includes full source, pin mapping, build/flash commands, and a validation workflow.


Prerequisites

  • Comfortable with:
  • ESP32 and PlatformIO on VS Code or CLI.
  • Basic DSP concepts (FFT, feature extraction, thresholds).
  • MQTT brokers and topics.
  • Soldering and breadboarding.
  • OS with serial driver support:
  • Windows: Silicon Labs CP210x USB-to-UART driver (for DevKitC’s CP2102/CP2104).
  • macOS: Typically driverless for CP210x, but install from Silicon Labs if needed.
  • Linux: Usually driverless; confirm device appears as /dev/ttyUSBx or /dev/tty.SLAB_USBtoUART.
  • Installed software:
  • PlatformIO Core (CLI) 6.x (tested with 6.1.11) or VS Code + PlatformIO extension.
  • Mosquitto clients for validation (mosquitto_pub, mosquitto_sub).
  • A working MQTT broker (e.g., Mosquitto on localhost or a network host).
  • Solid 5V power if you plan to drive a speaker from MAX98357A (ESP32’s 5V pin can power small loads via USB, but consider a separate supply if needed).

Materials (Exact Models)

  • Microcontroller: Espressif ESP32-DevKitC V4 (ESP32-WROOM-32)
  • Digital MEMS Microphone (I2S): INMP441
  • I2S DAC/Amplifier: MAX98357A (Adafruit MAX98357 I2S Class-D Mono Amp or equivalent breakout)
  • Addressable RGB LED: WS2812B (single LED or short strip; you can cut just one pixel from a strip)
  • Speaker: 4–8 Ω small speaker for MAX98357A output
  • Breadboard + jumpers
  • USB cable for ESP32 DevKitC
  • Optional level shifting for WS2812B data signal (often works at 3.3 V for a single LED, but best practice is to buffer)

Driver note:
– If your Espressif ESP32-DevKitC V4 enumerates as an unknown device on Windows, install the Silicon Labs CP210x driver from https://www.silabs.com/developers/usb-to-uart-bridge-vcp-drivers.


Setup/Connection

We will use two I2S peripherals in the ESP32:

  • I2S0 (RX) for INMP441 microphone capture.
  • I2S1 (TX) for audio output to MAX98357A.

And a separate GPIO for WS2812B data.

Recommended pin mapping (tested, doesn’t conflict with flash/boot pins):

  • INMP441 (I2S RX, 3.3V device):
  • VDD → 3V3
  • GND → GND
  • L/R → GND (selects Left channel)
  • SCK/BCLK → GPIO32
  • WS/LRCL → GPIO33
  • SD (DOUT) → GPIO34 (input-only pin)
  • MAX98357A (I2S TX, powered from 5V):
  • VIN → 5V
  • GND → GND
  • DIN → GPIO26
  • BCLK → GPIO27
  • LRC → GPIO25
  • SD/GAIN pin per board variant (tie high to enable or leave floating as per module; see your board’s datasheet)
  • Speaker → + and – outputs
  • WS2812B:
  • 5V → 5V
  • GND → GND (must share common ground with ESP32)
  • Data In → GPIO4
  • Place a 330–470 Ω resistor in series with the data line if possible; add a 1000 µF capacitor across 5V/GND near the LED strip if driving more than one LED (for a single LED, optional).

Power notes:
– The ESP32 DevKitC can supply limited current from 5V via USB. The MAX98357A plus a small speaker at moderate volume is typically fine. If you experience brownouts, provide an external 5V supply and connect grounds.

I2S details:
– Microphone (INMP441) outputs 24-bit samples, left-justified in I2S frames. We’ll capture as 32-bit and shift to 16-bit for DSP.
– MAX98357A reads standard I2S stereo (we’ll feed identical samples for L/R or generate a mono stream in both channels).


Table: Wiring Summary

Module Signal ESP32-DevKitC V4 GPIO/Pin Notes
INMP441 VDD 3V3 3.3V only
INMP441 GND GND Common ground
INMP441 L/R GND Select Left channel
INMP441 SCK/BCLK GPIO32 I2S0 BCLK (RX)
INMP441 WS/LRCL GPIO33 I2S0 LRCLK (RX)
INMP441 SD (DOUT) GPIO34 I2S0 Data In (input-only)
MAX98357A VIN 5V Power 5V
MAX98357A GND GND Common ground
MAX98357A DIN GPIO26 I2S1 Data Out (TX)
MAX98357A BCLK GPIO27 I2S1 BCLK (TX)
MAX98357A LRC GPIO25 I2S1 LRCLK (TX)
WS2812B VDD 5V Prefer stable 5V supply
WS2812B GND GND Must share ground
WS2812B Data In GPIO4 Add ~330 Ω series resistor if possible

Full Code

The project is structured for PlatformIO (Arduino framework). It uses:

  • I2S driver from ESP-IDF headers (via Arduino core) for both RX and TX.
  • FFT-based features using arduinoFFT.
  • MQTT via PubSubClient.
  • LED status via Adafruit NeoPixel.

Create a new PlatformIO project and replace the files as shown below.

platformio.ini

Place this in the project root.

; File: platformio.ini
[env:esp32dev]
platform = espressif32 @ 6.5.0
board = esp32dev
framework = arduino
board_build.flash_mode = dio
; optional: larger app partition if you add more features
; board_build.partitions = huge_app.csv

monitor_speed = 115200
monitor_filters = time, esp32_exception_decoder, default

lib_deps =
  arduinoFFT@^1.6.0
  knolleary/PubSubClient@^2.8
  adafruit/Adafruit NeoPixel@^1.12.0

build_flags =
  -DCORE_DEBUG_LEVEL=3
  -DARDUINO_USB_MODE=1
  -DWS2812_PIN=4
  -DMIC_BCLK=32
  -DMIC_LRCL=33
  -DMIC_DOUT=34
  -DSPK_BCLK=27
  -DSPK_LRCL=25
  -DSPK_DIN=26
  -DMQTT_TOPIC_PREFIX=\"device/esp32-anom\"
  -DMQTT_QOS=1

src/main.cpp

// File: src/main.cpp
#include <Arduino.h>
#include <WiFi.h>
#include <PubSubClient.h>
#include <Adafruit_NeoPixel.h>
#include <driver/i2s.h>
#include <arduinoFFT.h>

// ---------------------- User Configuration ----------------------
static const char* WIFI_SSID = "YOUR_WIFI_SSID";
static const char* WIFI_PASS = "YOUR_WIFI_PASSWORD";

// MQTT broker settings
static const char* MQTT_HOST = "192.168.1.100";
static const uint16_t MQTT_PORT = 1883;
static const char* MQTT_USER = "";  // optional
static const char* MQTT_PASS = "";  // optional

// Topics
#ifndef MQTT_TOPIC_PREFIX
#define MQTT_TOPIC_PREFIX "device/esp32-anom"
#endif

// ---------------------- I2S Config ------------------------------
// Microphone (I2S0 RX)
#ifndef MIC_BCLK
#define MIC_BCLK 32
#endif
#ifndef MIC_LRCL
#define MIC_LRCL 33
#endif
#ifndef MIC_DOUT
#define MIC_DOUT 34
#endif

// Speaker (I2S1 TX)
#ifndef SPK_BCLK
#define SPK_BCLK 27
#endif
#ifndef SPK_LRCL
#define SPK_LRCL 25
#endif
#ifndef SPK_DIN
#define SPK_DIN 26
#endif

// ---------------------- LED Config ------------------------------
#ifndef WS2812_PIN
#define WS2812_PIN 4
#endif
#define WS2812_COUNT 1

// ---------------------- DSP/Anomaly Config ----------------------
static const uint32_t SAMPLE_RATE = 16000;    // 16 kHz
static const size_t FFT_N = 512;              // 32 ms frame
static const size_t HOP = FFT_N;              // no overlap for simplicity
static const uint8_t NUM_BANDS = 16;          // coarse spectral bands
static const size_t BASELINE_FRAMES = 300;    // ~9.6 s baseline (300 * 32ms)
static const float ANOMALY_THRESHOLD = 25.0f; // sum |z| across bands

// ---------------------- Globals --------------------------------
WiFiClient espClient;
PubSubClient mqtt(espClient);

Adafruit_NeoPixel pixel(WS2812_COUNT, WS2812_PIN, NEO_GRB + NEO_KHZ800);

// FFT arrays
arduinoFFT FFT = arduinoFFT();
double vReal[FFT_N];
double vImag[FFT_N];

float bandMeans[NUM_BANDS];
float bandStd[NUM_BANDS];
bool baselineDone = false;
size_t baselineCount = 0;

char deviceId[32];

// ---------------------- Utilities -------------------------------
void setLED(uint8_t r, uint8_t g, uint8_t b) {
  pixel.setPixelColor(0, pixel.Color(r, g, b));
  pixel.show();
}

void ledPulseRed() {
  static uint8_t phase = 0;
  uint8_t level = (uint8_t)(127 + 127 * sin(phase * 0.1));
  setLED(level, 0, 0);
  phase++;
}

void ledGreenSolid() {
  setLED(0, 64, 0);
}

void ledBlueBlink() {
  static bool on = false;
  setLED(0, 0, on ? 64 : 0);
  on = !on;
}

void beepAlert(uint16_t freq = 1000, uint16_t ms = 200, uint16_t volume = 2000) {
  // Simple sine wave beep on I2S1 TX
  i2s_config_t i2s_config = {
    .mode = (i2s_mode_t)(I2S_MODE_MASTER | I2S_MODE_TX),
    .sample_rate = (int)SAMPLE_RATE,
    .bits_per_sample = I2S_BITS_PER_SAMPLE_16BIT,
    .channel_format = I2S_CHANNEL_FMT_RIGHT_LEFT,
    .communication_format = I2S_COMM_FORMAT_I2S_MSB,
    .intr_alloc_flags = ESP_INTR_FLAG_LEVEL1,
    .dma_buf_count = 8,
    .dma_buf_len = 256,
    .use_apll = false,
    .tx_desc_auto_clear = true,
    .fixed_mclk = 0
  };

  i2s_pin_config_t pin_config = {
    .bck_io_num = SPK_BCLK,
    .ws_io_num = SPK_LRCL,
    .data_out_num = SPK_DIN,
    .data_in_num = I2S_PIN_NO_CHANGE
  };

  i2s_driver_install(I2S_NUM_1, &i2s_config, 0, NULL);
  i2s_set_pin(I2S_NUM_1, &pin_config);
  i2s_set_clk(I2S_NUM_1, SAMPLE_RATE, I2S_BITS_PER_SAMPLE_16BIT, I2S_CHANNEL_STEREO);

  const uint32_t total_samples = (SAMPLE_RATE * ms) / 1000;
  const float omega = 2.0f * PI * freq / SAMPLE_RATE;

  for (uint32_t n = 0; n < total_samples; n++) {
    int16_t s = (int16_t)(volume * sinf(omega * n));
    uint32_t stereo = ((uint16_t)s << 16) | ((uint16_t)s);
    size_t written;
    i2s_write(I2S_NUM_1, &stereo, sizeof(stereo), &written, portMAX_DELAY);
  }

  i2s_driver_uninstall(I2S_NUM_1);
}

// Compute 16 log-energy bands from FFT magnitude
void computeBands(const double* mag, float* bands, size_t nfft, uint32_t fs) {
  // Frequency resolution
  const double df = (double)fs / (double)nfft;
  // Use pseudo-mel spacing over 0..8kHz (simple linear-to-log mapping)
  // Band edges exponentially spaced
  double fmin = 100.0, fmax = fs / 2.0;
  double logmin = log10(fmin);
  double logmax = log10(fmax);
  for (int b = 0; b < NUM_BANDS; b++) {
    double e0 = pow(10.0, logmin + (logmax - logmin) * b / NUM_BANDS);
    double e1 = pow(10.0, logmin + (logmax - logmin) * (b + 1) / NUM_BANDS);
    int k0 = (int)floor(e0 / df);
    int k1 = (int)ceil(e1 / df);
    if (k0 < 1) k0 = 1; // skip DC
    if (k1 >= (int)(nfft / 2)) k1 = (nfft / 2) - 1;

    double sum = 0.0;
    for (int k = k0; k <= k1; k++) {
      sum += mag[k] * mag[k]; // power
    }
    bands[b] = (sum > 1e-12) ? (float)log10(sum) : -12.0f;
  }
}

float updateBaselineAndScore(const float* bands) {
  if (!baselineDone) {
    // Welford-like online mean/std (keep running stats; std computed post)
    static double m[NUM_BANDS] = {0};
    static double s[NUM_BANDS] = {0};
    baselineCount++;
    for (int b = 0; b < NUM_BANDS; b++) {
      double x = bands[b];
      double delta = x - m[b];
      m[b] += delta / baselineCount;
      s[b] += delta * (x - m[b]);
    }
    if (baselineCount >= BASELINE_FRAMES) {
      for (int b = 0; b < NUM_BANDS; b++) {
        bandMeans[b] = (float)m[b];
        double var = (baselineCount > 1) ? s[b] / (baselineCount - 1) : 1e-3;
        bandStd[b] = (float)sqrt(var + 1e-6);
      }
      baselineDone = true;
    }
    return 0.0f; // no scoring during baseline
  } else {
    float score = 0.0f;
    for (int b = 0; b < NUM_BANDS; b++) {
      float z = (bands[b] - bandMeans[b]) / (bandStd[b] + 1e-6f);
      score += fabsf(z);
    }
    return score;
  }
}

void publishMQTT(const String& topic, const String& payload, bool retain = false) {
  String full = String(MQTT_TOPIC_PREFIX) + "/" + topic;
  mqtt.publish(full.c_str(), payload.c_str(), retain);
}

void connectWiFi() {
  WiFi.mode(WIFI_STA);
  WiFi.begin(WIFI_SSID, WIFI_PASS);
  Serial.printf("[WiFi] Connecting to %s\n", WIFI_SSID);
  uint32_t start = millis();
  while (WiFi.status() != WL_CONNECTED) {
    delay(500);
    Serial.print(".");
    ledBlueBlink();
    if (millis() - start > 30000) {
      Serial.println("\n[WiFi] Timeout, restarting...");
      ESP.restart();
    }
  }
  Serial.printf("\n[WiFi] Connected, IP: %s\n", WiFi.localIP().toString().c_str());
}

void connectMQTT() {
  mqtt.setServer(MQTT_HOST, MQTT_PORT);
  mqtt.setKeepAlive(30);
  while (!mqtt.connected()) {
    String clientId = String("esp32-anom-") + String(deviceId);
    Serial.printf("[MQTT] Connecting to %s as %s ...\n", MQTT_HOST, clientId.c_str());
    if (mqtt.connect(clientId.c_str(), MQTT_USER, MQTT_PASS)) {
      Serial.println("[MQTT] Connected");
      publishMQTT("status", "{\"state\":\"online\"}", true);
      publishMQTT("info", String("{\"device\":\"") + deviceId + "\",\"sr\":" + SAMPLE_RATE + ",\"fft\":" + FFT_N + "}");
    } else {
      Serial.printf("[MQTT] failed rc=%d, retrying in 3s\n", mqtt.state());
      delay(3000);
    }
  }
}

void initI2S_RX() {
  i2s_config_t i2s_config = {
    .mode = (i2s_mode_t)(I2S_MODE_MASTER | I2S_MODE_RX),
    .sample_rate = (int)SAMPLE_RATE,
    .bits_per_sample = I2S_BITS_PER_SAMPLE_32BIT,
    .channel_format = I2S_CHANNEL_FMT_ONLY_LEFT,
    .communication_format = I2S_COMM_FORMAT_I2S_MSB,
    .intr_alloc_flags = ESP_INTR_FLAG_LEVEL1,
    .dma_buf_count = 8,
    .dma_buf_len = 256,
    .use_apll = false,
    .tx_desc_auto_clear = false,
    .fixed_mclk = 0
  };
  i2s_pin_config_t pin_config = {
    .bck_io_num = MIC_BCLK,
    .ws_io_num = MIC_LRCL,
    .data_out_num = I2S_PIN_NO_CHANGE,
    .data_in_num = MIC_DOUT
  };
  i2s_driver_install(I2S_NUM_0, &i2s_config, 0, NULL);
  i2s_set_pin(I2S_NUM_0, &pin_config);
  i2s_set_clk(I2S_NUM_0, SAMPLE_RATE, I2S_BITS_PER_SAMPLE_32BIT, I2S_CHANNEL_MONO);
  Serial.println("[I2S] RX initialized");
}

void setup() {
  Serial.begin(115200);
  delay(200);

  // Unique device id
  uint64_t mac = ESP.getEfuseMac();
  snprintf(deviceId, sizeof(deviceId), "%04X%04X", (uint16_t)(mac >> 32), (uint32_t)(mac & 0xFFFF));

  pixel.begin();
  pixel.clear();
  pixel.show();
  setLED(0, 0, 32); // Blue: boot

  connectWiFi();
  connectMQTT();

  initI2S_RX();

  setLED(32, 32, 0); // Yellow: baseline learning
}

void loop() {
  mqtt.loop();

  // Buffer to read one frame
  static int32_t raw32[FFT_N];
  size_t bytes_read = 0;
  size_t want = sizeof(raw32);
  uint8_t* ptr = (uint8_t*)raw32;
  while (bytes_read < want) {
    size_t n = 0;
    esp_err_t err = i2s_read(I2S_NUM_0, ptr + bytes_read, want - bytes_read, &n, portMAX_DELAY);
    if (err != ESP_OK) {
      Serial.printf("[I2S] read error: %d\n", (int)err);
      break;
    }
    bytes_read += n;
  }

  // Convert to float/double for FFT, with 16-bit scaling
  // INMP441: 24-bit valid left-justified in 32-bit word
  // Shift right 8 to get 24->16 bits, then apply window
  double dc = 0.0;
  for (size_t i = 0; i < FFT_N; i++) {
    int32_t s32 = raw32[i] >> 8; // 24b -> 16b
    int16_t s16 = (int16_t)(s32 & 0xFFFF);
    double x = (double)s16 / 32768.0;
    vReal[i] = x;
    dc += x;
    vImag[i] = 0.0;
  }
  // Remove DC offset
  dc /= FFT_N;
  for (size_t i = 0; i < FFT_N; i++) {
    vReal[i] -= dc;
  }

  // Hann window
  for (size_t i = 0; i < FFT_N; i++) {
    vReal[i] *= 0.5 * (1.0 - cos((2.0 * PI * i) / (FFT_N - 1)));
  }

  // FFT
  FFT.Windowing(vReal, FFT_N, FFT_WIN_TYP_RECTANGLE, FFT_FORWARD); // already windowed manually
  FFT.Compute(vReal, vImag, FFT_N, FFT_FORWARD);
  FFT.ComplexToMagnitude(vReal, vImag, FFT_N);

  // Compute bands
  float bands[NUM_BANDS];
  computeBands(vReal, bands, FFT_N, SAMPLE_RATE);

  // Update baseline or compute score
  float score = updateBaselineAndScore(bands);

  static uint32_t lastPub = 0;
  uint32_t now = millis();

  if (!baselineDone) {
    if (now - lastPub > 1000) {
      String payload = String("{\"state\":\"baseline\",\"frames\":") + baselineCount + "}";
      publishMQTT("status", payload);
      lastPub = now;
    }
    // LED: yellow during baseline
    setLED(32, 32, 0);
  } else {
    // LED and beeper behavior
    if (score > ANOMALY_THRESHOLD) {
      ledPulseRed();
      beepAlert(1000, 150, 2500);
      // Publish anomaly event with summary
      String payload = String("{\"anomaly\":true,\"score\":") + String(score, 2) +
                       ",\"sr\":" + SAMPLE_RATE + ",\"fft\":" + FFT_N + "}";
      publishMQTT("anomaly", payload);
    } else {
      ledGreenSolid();
    }

    // Periodic metrics
    if (now - lastPub > 2000) {
      // publish a compressed band snapshot (first 5 for brevity) and score
      String payload = String("{\"score\":") + String(score, 2) + ",\"bands\":[";
      for (int i = 0; i < NUM_BANDS; i++) {
        payload += String(bands[i], 3);
        if (i < NUM_BANDS - 1) payload += ",";
      }
      payload += "]}";
      publishMQTT("metrics", payload);
      lastPub = now;
    }
  }
}

Notes on code:

  • I2S RX: Configured for 32-bit samples; the INMP441’s 24-bit payload is right-shifted to get a 16-bit normalized signal for processing.
  • Feature extraction: 16 log-power bands from the magnitude spectrum; baseline mean/std built online; the anomaly score is the sum of absolute z-scores.
  • MQTT: Periodically publishes metrics; sends an anomaly message when threshold is exceeded.
  • LED: Blue during boot; Yellow during baseline; Green when normal; pulsing Red on anomaly.
  • Audio: On anomaly, a short sine beep is generated and sent to MAX98357A via I2S1.

Build/Flash/Run Commands

Use PlatformIO Core (CLI). Ensure your USB serial port is recognized (e.g., COMx on Windows, /dev/ttyUSBx or /dev/tty.SLAB_USBtoUART on Linux/macOS).

Initialize (if creating from scratch):

pio project init --board esp32dev

Build:

pio run

Upload (auto-detects port):

pio run --target upload

Open serial monitor at 115200 baud:

pio device monitor -b 115200

If you have multiple serial devices, specify port:

pio device monitor -b 115200 -p /dev/ttyUSB0

Upgrade PlatformIO platforms if needed:

pio platform update espressif32

Step-by-step Validation

Follow these steps in order. Keep the serial monitor open to observe logs.

1) Power and Basic Bring-up
– Connect the ESP32-DevKitC V4 via USB.
– Verify the CP210x driver is installed if the serial port is missing.
– On reset, the LED should show blue, then yellow while baseline is building.

2) Verify Wi-Fi and MQTT Connectivity
– Ensure WIFI_SSID and WIFI_PASS are correct in main.cpp.
– Ensure MQTT_HOST and MQTT_PORT point to your broker.
– Monitor serial output:
– [WiFi] Connected, IP: …
– [MQTT] Connected
– Use mosquitto_sub to watch topics:

mosquitto_sub -h 192.168.1.100 -t "device/esp32-anom/#" -v

You should see “status”, “info”, and periodic “metrics” messages once baseline completes.

3) Verify Microphone Capture
– During baseline, keep the environment at normal noise levels. Speak or clap and observe that baseline count increases to 300 (~10 seconds).
– After baselineDone is true (shown implicitly by metrics messages), the LED should turn green when quiet.

4) Validate Anomaly Detection
– Create a distinct sound (e.g., jingling keys, whistle, or banging a cup).
– Observe:
– The LED should pulse red briefly during the event.
– You should hear a short beep from the speaker (MAX98357A).
– In mosquitto_sub, you should see an “anomaly” message like:
device/esp32-anom/anomaly {«anomaly»:true,»score»:38.42,»sr»:16000,»fft»:512}

5) Validate Metrics Payloads
– Monitor metrics payload content:
– Confirm “score” keeps low steady values when quiet and higher spikes during events.
– Confirm “bands” contains 16 values (log-power per band).

6) Test MQTT Retained Status
– Restart the ESP32; check that device/esp32-anom/status retains {«state»:»online»} after reconnection.
– Confirm the “info” message with device id, sample rate, FFT size is sent on connect.

7) Validate Speaker Output
– If no beep is heard, verify wiring to MAX98357A:
– DIN → GPIO26, BCLK → GPIO27, LRC → GPIO25, VIN → 5V, GND → GND.
– Try increasing beep volume parameter in beepAlert (e.g., 3000–6000). Beware of clipping and speaker limits.

8) Validate LED Behavior
– During baseline: Yellow.
– Normal: Green solid.
– Anomaly: Pulsing Red during the event.


Troubleshooting

  • Serial port missing (Windows):
  • Install Silicon Labs CP210x VCP driver.
  • Try a different USB cable or port.
  • Boot loops or random resets:
  • Power supply marginal. Lower speaker volume, use a powered USB hub, or provide a separate 5V supply for MAX98357A and LED. Always share grounds.
  • No MQTT messages:
  • Confirm broker IP and port.
  • Test with mosquitto_pub to ensure broker is reachable:
    mosquitto_pub -h 192.168.1.100 -t test -m hello
  • Ensure no firewall blocks port 1883.
  • No “anomaly” events:
  • The environment may be too consistent; try louder or more distinct acoustic events.
  • Lower ANOMALY_THRESHOLD (e.g., 18.0f).
  • Extend BASELINE_FRAMES (more stable baseline; also increases baseline time).
  • Microphone reads all zeros or garbage:
  • Verify INMP441 wiring. L/R must be tied to GND for Left. Ensure SD to GPIO34 (input-only).
  • Swap MIC_LRCL and MIC_BCLK if miswired.
  • Check that sample rate is compatible (16 kHz generally works; you can try 32 kHz or 48 kHz).
  • Distorted or missing beep:
  • Confirm MAX98357A SD/EN pin is not held low (some boards have SD pin; tie high).
  • Ensure I2S1 sample rate (16 kHz) matches beep generation and that speaker is connected properly.
  • WS2812B flicker or no light:
  • Ensure a common ground.
  • Add a 330–470 Ω resistor in series with the data line.
  • Try lowering data line length; ensure 5V power is stable.

Improvements

  • Use TLS for MQTT:
  • Switch to WiFiClientSecure and configure CA certs; use port 8883.
  • Smarter anomaly detection:
  • Replace band z-score with Mahalanobis distance using covariance matrix.
  • Compute MFCCs (requires DCT and mel filters) and train a baseline GMM or One-Class SVM offline, then run inference on-device.
  • Adaptive baseline:
  • Slowly adapt means/variance to non-anomalous drift to reduce false positives.
  • Overlap and windowing:
  • Use 50% overlap to improve time resolution; use Hanning or Blackman windows directly via FFT library for consistency.
  • On-device logging:
  • Send ring buffers of raw audio around anomaly to MQTT or to an SD card for offline analysis.
  • Multi-topic segregation:
  • Separate “metrics” and “events” into different QoS and retention policies.
  • Power optimization:
  • Use light sleep between frames; reduce sample rate when idle, increase upon suspected activity.
  • LED UI:
  • Map anomaly score to LED color (green to red gradient).
  • Calibrated thresholds:
  • Implement a calibration mode via MQTT command (e.g., device/esp32-anom/cmd) to restart baseline remotely.

Final Checklist

  • Hardware
  • Espressif ESP32-DevKitC V4 (ESP32-WROOM-32) connected via USB.
  • INMP441 wired: VDD→3V3, GND→GND, L/R→GND, SCK→GPIO32, WS→GPIO33, SD→GPIO34.
  • MAX98357A wired: VIN→5V, GND→GND, DIN→GPIO26, BCLK→GPIO27, LRC→GPIO25, speaker attached.
  • WS2812B wired: 5V→5V, GND→GND, Data→GPIO4 (optional 330 Ω resistor).
  • Software
  • PlatformIO installed; project contains platformio.ini and src/main.cpp as provided.
  • Wi-Fi and MQTT credentials configured in src/main.cpp.
  • Build succeeds via pio run.
  • Flash via pio run –target upload; serial monitor at 115200.
  • Validation
  • Device connects to Wi-Fi and MQTT; status/info messages published.
  • Baseline completes (yellow LED transitions to green).
  • Making a distinct sound triggers red LED pulse, beep, and MQTT anomaly message.
  • Metrics publish periodically and scores make sense.
  • Troubleshooting
  • If no anomaly triggers, adjust ANOMALY_THRESHOLD and verify sensor wiring.
  • If audio issues occur, recheck MAX98357A pin mapping and supply voltage.
  • If LED doesn’t light, verify WS2812 power, ground, and data pin.

With this setup, your Espressif ESP32-DevKitC V4 (ESP32-WROOM-32) + INMP441 + MAX98357A + WS2812B operates as a robust, real-time i2s-anomaly-detection-mqtt node, streaming health metrics, announcing anomalies with visual and audible cues, and providing a solid base for more advanced on-device audio analytics.

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 microphone is used in the ESP32 anomaly detection project?




Question 2: Which software is required to run the ESP32 project?




Question 3: What type of feedback does the WS2812B provide?




Question 4: Which MQTT client is mentioned for validation?




Question 5: What is the purpose of the MAX98357A in the project?




Question 6: What is the recommended OS for the serial driver support?




Question 7: What is the ESP32 model used in the project?




Question 8: What is a prerequisite for this project regarding DSP?




Question 9: What type of power supply is recommended for the MAX98357A?




Question 10: What is the main objective of the project?




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