Artificial Brain Controlled Robot

This video explains most of the things you need to know about making this artificial brain controlled robot. One thing missing was the code used in the two ESP-32 microcontroller to wirelesses send the signals back and forth. I will share instructions to upload the code and exact code I used.

This is the instructions for the new updated design. You will need to Update MAC addresses in both codes after finding them.

I already had a ELEGOO UNO R3 Smart Robot Car Kit so decided to use parts for that kit. I am just using the robot motors and frame. A  L298N Motor Driver Controller Board Module is used to supply power and control to the motors. The control command will be sent wirelessly form and ESP32 to ESP32.

The transmitter ESP32 on the vehicle sends out 4 channels of IR proximity sensor data to the receiving ESP32 on the breadboard of a hardware based neural network that determines the proper control signal to send out.

This signal is then sent out using six other channels of the ESP32 on the neural network side. The ESP32 on the vehicle receives these signals and sends them to the inputs of the L298N motor driver controller board module. There are 4 motors on the vehicle but the left and right motors will be wired in parallel so only one control board is needed. This will be powered with a 7.4v Lithium Battery Pack.

Here are the instructions for the code and wiring pin-out.

Wiring Summary

Neural Network ESP32:

Inputs coming

to Neural Network from Proximity sensors:

  • GPIO 13: Right sensor PWM output

  • GPIO 14: Front sensor PWM output

  • GPIO 26: Back sensor PWM output

  • GPIO 27: Left sensor PWM output

Outputs Sent from Neural Network to Robot:

  • GPIO 34: IN1 – Right Forward signal (0-3.3V) )

  • GPIO 35: IN2 – Right Reverse signal (0-3.3V)

  • GPIO 32: IN3 – Left Forward signal (0-3.3V)

  • GPIO 33: IN4 – Left Reverse signal (0-3.3V)

  • GPIO 36 VP: ENA – Right Speed signal (0-3.3V)

  • GPIO 39 VN: ENB – Left Speed signal (0-3.3V)

Robot ESP32:

Outputs IR Proximity Sensor Data to Neural Network:

  • GPIO 33: Right IR sensor

  • GPIO 32: Front IR sensor

  • GPIO 35: Back IR sensor

  • GPIO 34: Left IR sensor

Receives Data for Motor Control Outputs: (Also Used to Wire L2N8N)

  • GPIO 25: Right motor speed (ENB) – analog voltage 0-3.3V

  • GPIO 26: Right motor FORWARD (IN3) – HIGH=forward, LOW=not forward

  • GPIO 27: Right motor REVERSE (IN4) – HIGH=reverse, LOW=not reverse

  • GPIO 13: Left motor FORWARD (IN1) – HIGH=forward, LOW=not forward

  • GPIO 14: Left motor REVERSE (IN2) – HIGH=reverse, LOW=not reverse

  • GPIO 12: Left motor speed (ENA) – analog voltage 0-3.3V

Download Instructions

#include <WiFi.h>
void setup() {
  Serial.begin(115200);
  WiFi.mode(WIFI_STA);
  delay(1000);
  Serial.println(“ESP32 MAC Address:”);
  Serial.println(WiFi.macAddress());
}
void loop() {
  delay(1000);
}

Robot side Mac Address
MAC: f4:65:0b:54:5e:f0


Neural Network Side Mac Address
MAC: f4:65:0b:56:66:6c

Select ESP32 Board and Port

  1. Go to Tools > Board

  2. Look for “ESP32 Arduino” section and select “ESP32 Dev Module”

  3. Go to Tools > Port

  4. Select “COM3 (Silicon Labs CP210x USB to UART Bridge)”

(Neural Network/Breadboard Side)

Here is the full code. Make sure to paste it into the Arduino IDE.

// Complete Neural Network ESP32 Code – Reads 6 NN outputs, sends sensor data via PWM
#include <esp_now.h>
#include <WiFi.h>
#include <esp_wifi.h>  // Added for power saving control
#include <esp_task_wdt.h>
// Replace with your robot’s MAC address
uint8_t robotAddress[] = {0xF4, 0x65, 0x0B, 0x54, 0x5E, 0xF0};  // Robot MAC
// Structure for sensor data FROM robot – PACKED for consistency
typedef struct __attribute__((packed)) sensor_data {
  int sensor1;  // Right proximity
  int sensor2;  // Front proximity
  int sensor3;  // Back proximity
  int sensor4;  // Left proximity
} sensor_data;
// Structure for control data TO robot – PACKED for consistency
typedef struct __attribute__((packed)) control_data {
  int in1;    // Right forward (0-4095)
  int in2;    // Right reverse (0-4095)
  int in3;    // Left forward (0-4095)
  int in4;    // Left reverse (0-4095)
  int ena;    // Right speed (0-4095)
  int enb;    // Left speed (0-4095)
} control_data;
sensor_data incomingSensorData;
control_data outgoingControlData;
esp_now_peer_info_t peerInfo;
// Neural network control input pins – Read 6 separate outputs from your NN circuit
const int IN1_INPUT_PIN = 34;   // Right Forward
const int IN2_INPUT_PIN = 35;   // Right Reverse
const int IN3_INPUT_PIN = 32;   // Left Forward
const int IN4_INPUT_PIN = 33;   // Left Reverse
const int ENA_INPUT_PIN = 36;   // Right Speed (VP pin)
const int ENB_INPUT_PIN = 39;   // Left Speed (VN pin)
// Sensor output pins (to neural network) – PWM outputs
const int SENSOR1_OUT_PIN = 13;  // Right sensor output to NN
const int SENSOR2_OUT_PIN = 14;  // Front sensor output to NN
const int SENSOR3_OUT_PIN = 26;  // Back sensor output to NN
const int SENSOR4_OUT_PIN = 27;  // Left sensor output to NN
// PWM settings for sensor outputs to neural network
const int PWM_FREQ = 16000;
const int PWM_RESOLUTION = 8;
// Callback for receiving sensor data from robot
void OnDataRecv(const esp_now_recv_info *info, const uint8_t *incomingData, int len) {
  memcpy(&incomingSensorData, incomingData, sizeof(incomingSensorData));
  // Output sensor data to neural network via PWM (convert 12-bit to 8-bit)
  ledcWrite(SENSOR1_OUT_PIN, incomingSensorData.sensor1 / 16);
  ledcWrite(SENSOR2_OUT_PIN, incomingSensorData.sensor2 / 16);
  ledcWrite(SENSOR3_OUT_PIN, incomingSensorData.sensor3 / 16);
  ledcWrite(SENSOR4_OUT_PIN, incomingSensorData.sensor4 / 16);
}
// Callback for send status
void OnDataSent(const uint8_t *mac_addr, esp_now_send_status_t status) {
  // Silent – no overhead
}
void setup() {
  Serial.begin(115200);
  // Initialize WiFi in station mode
  WiFi.mode(WIFI_STA);
  // CRITICAL: Disable WiFi power saving for minimum latency
  esp_wifi_set_ps(WIFI_PS_NONE);
  WiFi.setSleep(false);  // Extra insurance against power saving
  // Initialize ESP-NOW
  if (esp_now_init() != ESP_OK) {
    Serial.println(“Error initializing ESP-NOW”);
    return;
  }
  // Register callbacks
  esp_now_register_recv_cb(OnDataRecv);
  esp_now_register_send_cb(OnDataSent);
  // Register peer (robot)
  memcpy(peerInfo.peer_addr, robotAddress, 6);
  peerInfo.channel = 0;
  peerInfo.encrypt = false;
  if (esp_now_add_peer(&peerInfo) != ESP_OK){
    Serial.println(“Failed to add peer”);
    return;
  }
  // Setup PWM for sensor outputs to neural network
  ledcAttach(SENSOR1_OUT_PIN, PWM_FREQ, PWM_RESOLUTION);
  ledcAttach(SENSOR2_OUT_PIN, PWM_FREQ, PWM_RESOLUTION);
  ledcAttach(SENSOR3_OUT_PIN, PWM_FREQ, PWM_RESOLUTION);
  ledcAttach(SENSOR4_OUT_PIN, PWM_FREQ, PWM_RESOLUTION);
  // Initialize watchdog
  esp_task_wdt_config_t twdt_config = {
    .timeout_ms = 5000,
    .idle_core_mask = 0,
    .trigger_panic = true
  };
  esp_task_wdt_init(&twdt_config);
  esp_task_wdt_add(NULL);
  Serial.println(“Neural Network ESP32 ready!”);
  Serial.print(“This ESP32 MAC: “);
  Serial.println(WiFi.macAddress());
  Serial.println(“WiFi power saving disabled for low latency”);
}
void loop() {
  esp_task_wdt_reset();
  // Read all 6 neural network control outputs
  outgoingControlData.in1 = analogRead(IN1_INPUT_PIN);  // Right Forward (0-4095)
  outgoingControlData.in2 = analogRead(IN2_INPUT_PIN);  // Right Reverse (0-4095)
  outgoingControlData.in3 = analogRead(IN3_INPUT_PIN);  // Left Forward (0-4095)
  outgoingControlData.in4 = analogRead(IN4_INPUT_PIN);  // Left Reverse (0-4095)
  outgoingControlData.ena = analogRead(ENA_INPUT_PIN);  // Right Speed (0-4095)
  outgoingControlData.enb = analogRead(ENB_INPUT_PIN);  // Left Speed (0-4095)
  // Send control data to robot
  esp_now_send(robotAddress, (uint8_t *) &outgoingControlData, sizeof(outgoingControlData));
  delay(5);  // 5ms update rate – optimal balance of speed and reliability
}

Full Updated Code for Robot

// Complete Robot ESP32 Code – Controls motors and reads sensors
#include <esp_now.h>
#include <WiFi.h>
#include <esp_wifi.h>  // Added for power saving control
#include <esp_task_wdt.h>
// Replace with your neural network ESP32’s MAC address
uint8_t neuralNetworkAddress[] = {0xF4, 0x65, 0x0B, 0x56, 0x66, 0x6C};  // NN Mac
// Structure for sensor data TO neural network – PACKED for consistency
typedef struct __attribute__((packed)) sensor_data {
  int sensor1;  // Right proximity
  int sensor2;  // Front proximity
  int sensor3;  // Back proximity
  int sensor4;  // Left proximity
} sensor_data;
// Structure for control data FROM neural network – PACKED for consistency
typedef struct __attribute__((packed)) control_data {
  int in1;    // Right forward (0-4095)
  int in2;    // Right reverse (0-4095)
  int in3;    // Left forward (0-4095)
  int in4;    // Left reverse (0-4095)
  int ena;    // Right speed (0-4095)
  int enb;    // Left speed (0-4095)
} control_data;
sensor_data outgoingSensorData;
control_data incomingControlData;
esp_now_peer_info_t peerInfo;
// IR Proximity sensor pins (updated to match actual wiring)
const int SENSOR1_PIN = 33;  // Right sensor – ADC1_CH5
const int SENSOR2_PIN = 32;  // Front sensor – ADC1_CH4
const int SENSOR3_PIN = 35;  // Back sensor  – ADC1_CH7 (input-only)
const int SENSOR4_PIN = 34;  // Left sensor  – ADC1_CH6 (input-only)
// Motor control pins (compatible with ELEGOO L298N)
const int ENA = 12;   // Left motor speed (PWM)
const int IN1 = 13;   // Left motor direction 1
const int IN2 = 14;   // Left motor direction 2
const int ENB = 25;   // Right motor speed (PWM)
const int IN3 = 26;   // Right motor direction 1
const int IN4 = 27;   // Right motor direction 2
// PWM settings for motors
const int MOTOR_PWM_FREQ = 1000;  // 1kHz for L298N
const int MOTOR_PWM_RESOLUTION = 8;  // 8-bit (0-255)
// Convert 12-bit ADC (0-4095) to 8-bit PWM (0-255)
int convert12to8bit(int value12bit) {
  return constrain(value12bit / 16, 0, 255);
}
// Convert 12-bit ADC (0-4095) to digital HIGH/LOW with threshold
bool convertToDigital(int value12bit, int threshold = 2048) {
  return value12bit > threshold;
}
// Callback for receiving control data from neural network
void OnDataRecv(const esp_now_recv_info *info, const uint8_t *incomingData, int len) {
  memcpy(&incomingControlData, incomingData, sizeof(incomingControlData));
  // Convert neural network outputs to motor control
  // Direction control (digital – above/below threshold)
  bool leftForward = convertToDigital(incomingControlData.in3);   // IN3 = Left Forward
  bool leftReverse = convertToDigital(incomingControlData.in4);   // IN4 = Left Reverse
  bool rightForward = convertToDigital(incomingControlData.in1);  // IN1 = Right Forward
  bool rightReverse = convertToDigital(incomingControlData.in2);  // IN2 = Right Reverse
  // Speed control (analog – convert 12-bit to 8-bit)
  int leftSpeed = convert12to8bit(incomingControlData.enb);       // ENB = Left Speed
  int rightSpeed = convert12to8bit(incomingControlData.ena);      // ENA = Right Speed
  // Control left motor
  if (leftForward && !leftReverse) {
    // Forward
    digitalWrite(IN1, HIGH);
    digitalWrite(IN2, LOW);
    ledcWrite(ENA, leftSpeed);
  } else if (leftReverse && !leftForward) {
    // Reverse
    digitalWrite(IN1, LOW);
    digitalWrite(IN2, HIGH);
    ledcWrite(ENA, leftSpeed);
  } else {
    // Stop (both signals active or both inactive)
    digitalWrite(IN1, LOW);
    digitalWrite(IN2, LOW);
    ledcWrite(ENA, 0);
  }
  // Control right motor
  if (rightForward && !rightReverse) {
    // Forward
    digitalWrite(IN3, HIGH);
    digitalWrite(IN4, LOW);
    ledcWrite(ENB, rightSpeed);
  } else if (rightReverse && !rightForward) {
    // Reverse
    digitalWrite(IN3, LOW);
    digitalWrite(IN4, HIGH);
    ledcWrite(ENB, rightSpeed);
  } else {
    // Stop (both signals active or both inactive)
    digitalWrite(IN3, LOW);
    digitalWrite(IN4, LOW);
    ledcWrite(ENB, 0);
  }
}
// Callback for send status
void OnDataSent(const uint8_t *mac_addr, esp_now_send_status_t status) {
  // Silent – no overhead
}
void setup() {
  Serial.begin(115200);
  // Setup motor control pins
  pinMode(IN1, OUTPUT);
  pinMode(IN2, OUTPUT);
  pinMode(IN3, OUTPUT);
  pinMode(IN4, OUTPUT);
  // Setup PWM for motor speed control
  ledcAttach(ENA, MOTOR_PWM_FREQ, MOTOR_PWM_RESOLUTION);
  ledcAttach(ENB, MOTOR_PWM_FREQ, MOTOR_PWM_RESOLUTION);
  // Initialize motors stopped
  digitalWrite(IN1, LOW);
  digitalWrite(IN2, LOW);
  digitalWrite(IN3, LOW);
  digitalWrite(IN4, LOW);
  ledcWrite(ENA, 0);
  ledcWrite(ENB, 0);
  // Initialize WiFi
  WiFi.mode(WIFI_STA);
  // CRITICAL: Disable WiFi power saving for minimum latency
  esp_wifi_set_ps(WIFI_PS_NONE);
  WiFi.setSleep(false);  // Extra insurance against power saving
  // Initialize ESP-NOW
  if (esp_now_init() != ESP_OK) {
    Serial.println(“Error initializing ESP-NOW”);
    return;
  }
  // Register callbacks
  esp_now_register_recv_cb(OnDataRecv);
  esp_now_register_send_cb(OnDataSent);
  // Register peer (neural network ESP32)
  memcpy(peerInfo.peer_addr, neuralNetworkAddress, 6);
  peerInfo.channel = 0;
  peerInfo.encrypt = false;
  if (esp_now_add_peer(&peerInfo) != ESP_OK){
    Serial.println(“Failed to add peer”);
    return;
  }
  // Initialize watchdog
  esp_task_wdt_config_t twdt_config = {
    .timeout_ms = 5000,
    .idle_core_mask = 0,
    .trigger_panic = true
  };
  esp_task_wdt_init(&twdt_config);
  esp_task_wdt_add(NULL);
  Serial.println(“Robot ESP32 ready!”);
  Serial.print(“This ESP32 MAC: “);
  Serial.println(WiFi.macAddress());
  Serial.println(“WiFi power saving disabled for low latency”);
}
void loop() {
  esp_task_wdt_reset();
  // Read all proximity sensors
  outgoingSensorData.sensor1 = analogRead(SENSOR1_PIN);  // Right = GPIO 33
  outgoingSensorData.sensor2 = analogRead(SENSOR2_PIN);  // Front = GPIO 32
  outgoingSensorData.sensor3 = analogRead(SENSOR3_PIN);  // Back = GPIO 35
  outgoingSensorData.sensor4 = analogRead(SENSOR4_PIN);  // Left = GPIO 34
  // Send sensor data to neural network
  esp_now_send(neuralNetworkAddress, (uint8_t *) &outgoingSensorData, sizeof(outgoingSensorData));
  delay(5);  // 5ms update rate – optimal balance of speed and reliability
}

 

Leave a Comment