Abhinav KrishnaAmritha M
Published © MIT

EleTect 2.0

Human wildlife conflict, poaching, and forest fires threaten both biodiversity and communities. EleTect is a family of Edge AI devices

IntermediateFull instructions providedOver 15 days79
EleTect 2.0

Things used in this project

Hardware components

Seeed Studio XIAO ESP32S3 Sense
Seeed Studio XIAO ESP32S3 Sense
×1
grove vision ai v2
×1
Raspberry pi IR camera
×1
df player mini
×1
Speaker: 3W, 4 ohms
Speaker: 3W, 4 ohms
×1
meshtatic wio sx1262
×1
Solar Power Manager (for 9V/12V/18V solar panel)
DFRobot Solar Power Manager (for 9V/12V/18V solar panel)
×1
solar panel 50 W
×1
sht10 sensor
×1
PM 2.5 SENSOR
×1
AVIATION CONNECTOR
×1

Software apps and online services

Edge Impulse Studio
Edge Impulse Studio
sensecraft ai
roboflow
google collab

Hand tools and fabrication machines

Soldering iron (generic)
Soldering iron (generic)
3D Printer (generic)
3D Printer (generic)
Laser cutter (generic)
Laser cutter (generic)

Story

Read more

Custom parts and enclosures

EleTect 2.0

Full design files

Schematics

schematic

Full schematics

Code

Code

C/C++
/**************************************************************
 * EleTect 2.0 — COMPLETE FUSED SKETCH
 * Board: Seeed XIAO ESP32-S3 Sense
 *
 * Features:
 *  - AUDIO (Edge Impulse): elephant_call, boar_grunt, chainsaw, gunshot, vehicle, background
 *  - VISION (Grove Vision AI V2 + SSCMA): elephant, boar
 *  - DFPLAYER deterrents:
 *      Track 1 -> bee buzz (elephant)
 *      Track 2 -> predator (boar)
 *      Track 3 -> siren (optional)
 *      Track 4 -> chainsaw tone (optional)
 *      Track 5 -> gunshot tone (optional)
 *      Track 6 -> vehicle tone (optional)
 *  - LoRa P2P (SX1262 / Wio SX1262 for XIAO) via RadioLib
 *  - RTC + SD CSV logging: timestamp,source,class,confidence
 **************************************************************/

// ================== REQUIRED LIBRARIES ==================
// Install: RadioLib, DFRobotDFPlayerMini, RTClib, Seeed_Arduino_SSCMA
// Include your Edge Impulse audio export (adds EleTect_inferencing.h)

// ---- Edge Impulse audio model export ----
#include <EleTect_inferencing.h>

// ---- ESP32 includes for audio I2S ----
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "driver/i2s.h"

// ---- Grove Vision AI V2 (SSCMA) ----
#include <Seeed_Arduino_SSCMA.h>
SSCMA AI;

// ---- LoRa SX1262 (RadioLib) ----
#include <RadioLib.h>

// ---- DFPlayer Mini ----
#include <HardwareSerial.h>
#include <DFRobotDFPlayerMini.h>

// ---- Logging (RTC + SD) ----
#include <RTClib.h>
#include <SD.h>
#include <SPI.h>

// ================== USER CONFIG (EDIT) ==================

// ---------- DFPLAYER UART PINS (XIAO ESP32-S3) ----------
HardwareSerial dfSerial(1);
// TODO: Set these to the pins you wired to DFPlayer:
static const int DF_TX_PIN = 10;  // XIAO TX -> DFPlayer RX
static const int DF_RX_PIN = 9;   // XIAO RX -> DFPlayer TX

DFRobotDFPlayerMini dfPlayer;

// ---------- SX1262 PINS (SEEED KIT PINOUT) ---------------
// Replace with exact pins from your Seeed wiki/carrier board
static const int LORA_NSS_PIN  = 7;   // CS/NSS
static const int LORA_DIO1_PIN = 1;   // DIO1
static const int LORA_RST_PIN  = 2;   // RESET
static const int LORA_BUSY_PIN = 0;   // BUSY
// If your SPI pins are not default, call SPI.begin(SCK, MISO, MOSI, LORA_NSS_PIN);

// LoRa Frequency (match regional regs and all nodes)
float LORA_FREQ_MHZ = 865.0;  // e.g., 865–867 (IN), 868 (EU), 915 (US)
SX1262 radio = new Module(LORA_NSS_PIN, LORA_DIO1_PIN, LORA_RST_PIN, LORA_BUSY_PIN);

// ---------- AUDIO I2S PINS (XIAO ESP32-S3 Sense MIC) -----
static const int I2S_BCLK = 26;
static const int I2S_WS   = 32;
static const int I2S_DIN  = 33;

// ---------- LOGGING (RTC + SD) ---------------------------
static const int SD_CS_PIN = 21;      // XIAO Sense onboard SD: CS=21
const char* LOG_DIR  = "/logs";
const char* LOG_FILE = "/logs/events.csv";
RTC_DS3231 rtc;
bool rtcOk = false;
bool sdOk  = false;

// ---------- CLASS THRESHOLDS & COOLDOWN ------------------
const float TH_ELPH = 0.70f;
const float TH_BOAR = 0.70f;
const float TH_SAW  = 0.80f;
const float TH_GUN  = 0.80f;
const float TH_VEH  = 0.80f;

const uint32_t COOLDOWN_MS = 10 * 1000; // 10 s debounce for alerts

// ---------- DFPLAYER TRACK MAP ---------------------------
const uint8_t TRK_ELEPHANT = 1; // 01_bee_buzz.mp3
const uint8_t TRK_BOAR     = 2; // 02_predator.mp3
const uint8_t TRK_SIREN    = 3; // 03_siren.mp3 (optional)
const uint8_t TRK_SAW      = 4; // 04_chainsaw.mp3 (optional)
const uint8_t TRK_GUN      = 5; // 05_gunshot.mp3 (optional)
const uint8_t TRK_VEH      = 6; // 06_vehicle.mp3 (optional)

// ---------- VISION POLLING RATE --------------------------
uint32_t lastVisionMs   = 0;
const uint32_t VISION_PERIOD_MS = 300;

// ---------- COOLDOWN STATE -------------------------------
uint32_t lastElephantMs = 0;
uint32_t lastBoarMs     = 0;
uint32_t lastSawMs      = 0;
uint32_t lastGunMs      = 0;
uint32_t lastVehMs      = 0;

// ================== AUDIO INFERENCE STATE =================

typedef struct {
  int16_t *buffer;
  uint8_t buf_ready;
  uint32_t buf_count;
  uint32_t n_samples;
} inference_t;

static inference_t inference;
static const uint32_t sample_buffer_size = 2048;
static int16_t sampleBuffer[sample_buffer_size];
static bool debug_nn = false;
static bool record_status = true;

// ================== HELPERS ===============================

void playTrack(uint8_t t) {
  // Drain DFPlayer status quickly to avoid blocking
  if (dfPlayer.available()) {
    (void)dfPlayer.readType();
    (void)dfPlayer.read();
  }
  dfPlayer.play(t);
}

void playDeterrentElephant() { playTrack(TRK_ELEPHANT); }
void playDeterrentBoar()     { playTrack(TRK_BOAR);     }

bool cooldownExpired(uint32_t &lastMs) {
  uint32_t now = millis();
  if (now - lastMs >= COOLDOWN_MS) {
    lastMs = now;
    return true;
  }
  return false;
}

// ---- LoRa send ----
void sendLoRa(const String& msg) {
  int16_t state = radio.transmit(msg);
  if (state == RADIOLIB_ERR_NONE) {
    Serial.print("[LoRa] TX OK: ");
    Serial.println(msg);
  } else {
    Serial.print("[LoRa] TX fail, code=");
    Serial.println(state);
  }
}

// ---- Timestamp & Logging ----
String two(int v) { return (v < 10) ? "0" + String(v) : String(v); }

String getTimestamp() {
  if (!rtcOk) return "1970-01-01 00:00:00";
  DateTime now = rtc.now();
  return String(now.year()) + "-" + two(now.month()) + "-" + two(now.day()) + " " +
         two(now.hour()) + ":" + two(now.minute()) + ":" + two(now.second());
}

void ensureLogHeader() {
  if (!sdOk) return;
  if (!SD.exists(LOG_DIR)) SD.mkdir(LOG_DIR);
  if (!SD.exists(LOG_FILE)) {
    File f = SD.open(LOG_FILE, FILE_WRITE);
    if (f) {
      f.println("timestamp,source,class,confidence");
      f.close();
    }
  }
}

void logEventCSV(const String& source, const String& clazz, float conf) {
  if (!sdOk) return;
  File f = SD.open(LOG_FILE, FILE_APPEND);
  if (!f) return;
  f.println(getTimestamp() + "," + source + "," + clazz + "," + String(conf, 3));
  f.close();
  Serial.printf("[LOG] %s,%s,%.3f\n", source.c_str(), clazz.c_str(), conf);
}

void logEvent(const char* source, const char* clazz, float conf) {
  logEventCSV(String(source), String(clazz), conf);
}

// ---- Unified event handler (deterrent + LoRa + cooldown) ----
void handleEvent(const char* evt) {
  String msg = evt;

  if (msg == "ELEPHANT") {
    if (cooldownExpired(lastElephantMs)) {
      playDeterrentElephant();
      sendLoRa("ELEPHANT");
      Serial.println("[EVENT] ELEPHANT");
    }
    return;
  }

  if (msg == "BOAR") {
    if (cooldownExpired(lastBoarMs)) {
      playDeterrentBoar();
      sendLoRa("BOAR");
      Serial.println("[EVENT] BOAR");
    }
    return;
  }

  if (msg == "ILLEGAL:chainsaw") {
    if (cooldownExpired(lastSawMs)) {
      sendLoRa("ILLEGAL:chainsaw");
      Serial.println("[EVENT] CHAINSAW");
    }
    return;
  }

  if (msg == "ILLEGAL:gunshot") {
    if (cooldownExpired(lastGunMs)) {
      sendLoRa("ILLEGAL:gunshot");
      Serial.println("[EVENT] GUNSHOT");
    }
    return;
  }

  if (msg == "VEHICLE") {
    if (cooldownExpired(lastVehMs)) {
      sendLoRa("VEHICLE");
      Serial.println("[EVENT] VEHICLE");
    }
    return;
  }
}

// ================== AUDIO (Edge Impulse) ==================

static void audio_inference_callback(uint32_t n_bytes) {
  for (int i = 0; i < n_bytes >> 1; i++) {
    inference.buffer[inference.buf_count++] = sampleBuffer[i];
    if (inference.buf_count >= inference.n_samples) {
      inference.buf_count = 0;
      inference.buf_ready = 1;
    }
  }
}

static void capture_samples(void* arg) {
  const int32_t i2s_bytes_to_read = (uint32_t)arg;
  size_t bytes_read = i2s_bytes_to_read;

  while (record_status) {
    i2s_read((i2s_port_t)1, (void*)sampleBuffer, i2s_bytes_to_read, &bytes_read, 100);
    if (bytes_read > 0) {
      // gain
      for (int x = 0; x < i2s_bytes_to_read/2; x++) {
        sampleBuffer[x] = (int16_t)(sampleBuffer[x]) * 8;
      }
      if (record_status) audio_inference_callback(i2s_bytes_to_read);
      else break;
    }
  }
  vTaskDelete(NULL);
}

static int i2s_init(uint32_t sampling_rate) {
  i2s_config_t i2s_config = {
    .mode = (i2s_mode_t)(I2S_MODE_MASTER | I2S_MODE_RX | I2S_MODE_TX),
    .sample_rate = (int)sampling_rate,
    .bits_per_sample = I2S_BITS_PER_SAMPLE_16BIT,
    .channel_format = I2S_CHANNEL_FMT_ONLY_RIGHT,
    .communication_format = I2S_COMM_FORMAT_I2S,
    .intr_alloc_flags = 0,
    .dma_buf_count = 8,
    .dma_buf_len = 512,
    .use_apll = false,
    .tx_desc_auto_clear = false,
    .fixed_mclk = -1,
  };
  i2s_pin_config_t pin_config = {
    .bck_io_num = I2S_BCLK,
    .ws_io_num = I2S_WS,
    .data_out_num = -1,
    .data_in_num = I2S_DIN,
  };
  esp_err_t ret = 0;
  ret = i2s_driver_install((i2s_port_t)1, &i2s_config, 0, NULL);
  if (ret != ESP_OK) return ret;
  ret = i2s_set_pin((i2s_port_t)1, &pin_config);
  if (ret != ESP_OK) return ret;
  ret = i2s_zero_dma_buffer((i2s_port_t)1);
  return ret;
}

static int i2s_deinit(void) {
  i2s_driver_uninstall((i2s_port_t)1);
  return 0;
}

static bool microphone_inference_start(uint32_t n_samples) {
  inference.buffer = (int16_t *)malloc(n_samples * sizeof(int16_t));
  if (inference.buffer == NULL) return false;
  inference.buf_count = 0;
  inference.n_samples = n_samples;
  inference.buf_ready = 0;

  if (i2s_init(EI_CLASSIFIER_FREQUENCY)) {
    ei_printf("Failed to start I2S!");
    return false;
  }
  ei_sleep(100);
  record_status = true;
  xTaskCreate(capture_samples, "CaptureSamples", 1024 * 32, (void*)sample_buffer_size, 10, NULL);
  return true;
}

static bool microphone_inference_record(void) {
  while (inference.buf_ready == 0) { delay(10); }
  inference.buf_ready = 0;
  return true;
}

static int microphone_audio_signal_get_data(size_t offset, size_t length, float *out_ptr) {
  numpy::int16_to_float(&inference.buffer[offset], out_ptr, length);
  return 0;
}

// ================== SETUP ==================

void setup() {
  Serial.begin(115200);
  while(!Serial) {}
  Serial.println("\nEleTect 2.0 — Fused (Audio + Vision + LoRa + DFPlayer + Logging)");

  // ---- DFPlayer ----
  dfSerial.begin(9600, SERIAL_8N1, DF_RX_PIN, DF_TX_PIN);
  if (!dfPlayer.begin(dfSerial)) {
    Serial.println("DFPlayer init failed (check wiring & SD). Continuing without sound.");
  } else {
    dfPlayer.volume(25); // 0..30
    Serial.println("DFPlayer OK.");
  }

  // ---- LoRa (SX1262 via RadioLib) ----
  // If needed for your carrier: SPI.begin(SCK, MISO, MOSI, LORA_NSS_PIN);
  int16_t state = radio.begin(LORA_FREQ_MHZ, 125.0, 9, 7, 0x34, 10, 8, 0);
  if (state == RADIOLIB_ERR_NONE) {
    Serial.println("LoRa init OK.");
  } else {
    Serial.print("LoRa init failed, code=");
    Serial.println(state);
  }

  // ---- Vision (SSCMA) ----
  AI.begin();
  Serial.println("SSCMA init done.");

  // ---- RTC ----
  if (rtc.begin()) {
    // If RTC lost power once, set the time with:
    // rtc.adjust(DateTime(F(__DATE__), F(__TIME__)));
    rtcOk = true;
    Serial.println("RTC DS3231 OK.");
  } else {
    rtcOk = false;
    Serial.println("RTC init failed (check wiring).");
  }

  // ---- SD ----
  if (SD.begin(SD_CS_PIN)) {
    sdOk = true;
    ensureLogHeader();
    Serial.println("SD OK, logging enabled.");
  } else {
    sdOk = false;
    Serial.println("SD init failed (check CS & card).");
  }

  // ---- Audio (Edge Impulse) ----
  ei_printf("Inferencing settings:\n");
  ei_printf("\tInterval: "); ei_printf_float((float)EI_CLASSIFIER_INTERVAL_MS); ei_printf(" ms\n");
  ei_printf("\tFrame size: %d\n", EI_CLASSIFIER_DSP_INPUT_FRAME_SIZE);
  ei_printf("\tSample length: %d ms\n", EI_CLASSIFIER_RAW_SAMPLE_COUNT / 16);
  ei_printf("\tNo. of classes: %d\n", sizeof(ei_classifier_inferencing_categories) / sizeof(ei_classifier_inferencing_categories[0]));

  if (!microphone_inference_start(EI_CLASSIFIER_RAW_SAMPLE_COUNT)) {
    ei_printf("ERR: Could not allocate audio buffer.\n");
  } else {
    ei_printf("Audio recording started.\n");
  }
}

// ================== LOOP ==================

void loop() {
  // ---- AUDIO INFERENCE ----
  if (microphone_inference_record()) {
    signal_t signal;
    signal.total_length = EI_CLASSIFIER_RAW_SAMPLE_COUNT;
    signal.get_data = &microphone_audio_signal_get_data;

    ei_impulse_result_t result = { 0 };
    EI_IMPULSE_ERROR r = run_classifier(&signal, &result, debug_nn);
    if (r == EI_IMPULSE_OK) {
      // Determine max class
      const char* maxLabel = nullptr;
      float maxVal = -1.0f;

      for (size_t ix = 0; ix < EI_CLASSIFIER_LABEL_COUNT; ix++) {
        const char* label = result.classification[ix].label;
        float val = result.classification[ix].value;
        if (val > maxVal) { maxVal = val; maxLabel = label; }
      }

      if (maxLabel != nullptr) {
        if (strcmp(maxLabel, "elephant_call") == 0 && maxVal >= TH_ELPH) {
          logEvent("audio", "elephant", maxVal);
          handleEvent("ELEPHANT");
        } else if (strcmp(maxLabel, "boar_grunt") == 0 && maxVal >= TH_BOAR) {
          logEvent("audio", "boar", maxVal);
          handleEvent("BOAR");
        } else if (strcmp(maxLabel, "chainsaw") == 0 && maxVal >= TH_SAW) {
          logEvent("audio", "chainsaw", maxVal);
          playTrack(TRK_SAW); // optional tone
          handleEvent("ILLEGAL:chainsaw");
        } else if (strcmp(maxLabel, "gunshot") == 0 && maxVal >= TH_GUN) {
          logEvent("audio", "gunshot", maxVal);
          playTrack(TRK_GUN);
          handleEvent("ILLEGAL:gunshot");
        } else if (strcmp(maxLabel, "vehicle") == 0 && maxVal >= TH_VEH) {
          logEvent("audio", "vehicle", maxVal);
          playTrack(TRK_VEH);
          handleEvent("VEHICLE");
        }
      }
    }
  }

  // ---- VISION INFERENCE (periodic, non-blocking) ----
  uint32_t now = millis();
  if (now - lastVisionMs >= VISION_PERIOD_MS) {
    lastVisionMs = now;

    // invoke once, no filter, not contain image
    if (!AI.invoke(1, false, false)) {
      auto &boxes = AI.boxes();
      for (size_t i = 0; i < boxes.size(); i++) {
        // SSCMA box has .score (0..100), .label (String)
        int score = boxes[i].score;
        String label = boxes[i].label;
        float conf = score / 100.0f;

        if (score > 80) {
          if (label == "elephant") {
            logEvent("vision", "elephant", conf);
            handleEvent("ELEPHANT");
          } else if (label == "boar") {
            logEvent("vision", "boar", conf);
            handleEvent("BOAR");
          }
        }
      }
    }
  }
}

Full codes

Credits

Abhinav Krishna
9 projects • 56 followers
Maker | IoT Enthusiast | Electronics hobbyist
Amritha M
3 projects • 8 followers

Comments