Read MAC Address:
#include "WiFi.h"
void setup(){
Serial.begin(115200);
WiFi.mode(WIFI_MODE_STA);
Serial.println(WiFi.macAddress());
}
void loop()
{
}
Connections: GND,--->GND, 6V----> Vin; ADXL335: X axis----->GPIO36, Y-axis---->GPIO39, GND-->GND, Vin--->3.3V
Transmitter Code
// Include Libraries
#include <esp_now.h>
#include <WiFi.h>
// Variables for sensor data
int int_valueX;
int int_valueY;
// MAC Address of responder - edit as required
uint8_t broadcastAddress[] = {0x08, 0xD1, 0xF9, 0xC8, 0xD5, 0x68};
// Define a data structure
typedef struct struct_message {
int a;
int b;
} struct_message;
// Create a structured object
struct_message myData;
// Peer info
esp_now_peer_info_t peerInfo;
// Callback function called when data is sent
void OnDataSent(const uint8_t *mac_addr, esp_now_send_status_t status) {
Serial.print("\r\nLast Packet Send Status:\t");
Serial.println(status == ESP_NOW_SEND_SUCCESS ? "Delivery Success" : "Delivery Fail");
}
void setup() {
// Set up Serial Monitor
Serial.begin(115200);
// Set ESP32 as a Wi-Fi Station
WiFi.mode(WIFI_STA);
// Initialize ESP-NOW
if (esp_now_init() != ESP_OK) {
Serial.println("Error initializing ESP-NOW");
return;
}
// Register the send callback
esp_now_register_send_cb(OnDataSent);
// Register peer
memcpy(peerInfo.peer_addr, broadcastAddress, 6);
peerInfo.channel = 0;
peerInfo.encrypt = false;
// Add peer
if (esp_now_add_peer(&peerInfo) != ESP_OK){
Serial.println("Failed to add peer");
return;
}
}
void loop() {
// Read tilt data
int_valueX = analogRead(36); //read analog X value from ADXL335 accelerometer
int_valueY = analogRead(39); //read analog Y value from ADXL335 accelerometer
// Format structured data
myData.a = int_valueX;
myData.b = int_valueY;
// Send message via ESP-NOW
esp_err_t result = esp_now_send(broadcastAddress, (uint8_t *) &myData, sizeof(myData));
if (result == ESP_OK) {
Serial.println("Sending confirmed");
}
else {
Serial.println("Sending error");
}
delay(200);
}
Connections: GND--->GND, 6V----->Vin; 6V---->Vcc in on L298; ENA---->GPIO25, ENB---->GPIO33, IN1---->GPIO32, IN2---->GPIO12, IN3---->GPIO18, IN4----->GPIO4; Echo sensor
#include <esp_now.h>
#include <WiFi.h>
// Callback function for receiving data
void OnDataRecv(const uint8_t *mac, const uint8_t *incomingData, int len) {
Serial.print("Received data of size: ");
Serial.println(len);
}
void setup() {
Serial.begin(115200);
// Set device in Station mode
WiFi.mode(WIFI_STA);
// Initialize ESP-NOW
if (esp_now_init() != ESP_OK) {
Serial.println("ESP-NOW initialization failed!");
return;
}
// Register the receive callback
esp_now_register_recv_cb(OnDataRecv);
}
void loop() {
// Nothing needed in loop for receiving ESP-NOW messages
}
Code for Robot Car(Receiver):
#include <esp_now.h>
#include <WiFi.h>
int valueX = 0;
int valueY = 0;
// Define a data structure
typedef struct struct_message {
int a;
int b;
} struct_message;
// Create a structured object
struct_message myData;
// Callback function executed when data is received
/*
void OnDataRecv(const uint8_t *mac, const uint8_t *incomingData, int len) {
Serial.print("Received data of size: ");
Serial.println(len); */
void OnDataRecv(const uint8_t *mac, const uint8_t *incomingData, int len) {
memcpy(&myData, incomingData, sizeof(myData));
Serial.print("Data received: ");
Serial.println(len);
Serial.print("X-axisValue: ");
Serial.println(myData.a);
Serial.print("Y-axis Value: ");
Serial.println(myData.b);
valueX = myData.a;
valueY = myData.b;
valueX = valueX - 1800; // map values to -400 to 400
valueY = valueY - 1800; // map values to -400 to 400
}
int enableleftPin = 25; // EN1 on L298N
int motorleftPin1 = 32; // IN1 on L298N
int motorleftPin2 = 12; // IN2 on L298N
//Assign pins for right motor
int enablerightPin = 33; // EN2 on L298N
int motorrightPin1 = 18; // IN3 on L298N
int motorrightPin2 = 4; // IN4 on L298N
void setup() {
// Set up Serial Monitor
Serial.begin(115200);
// Set ESP32 as a Wi-Fi Station
WiFi.mode(WIFI_STA);
// Initialize ESP-NOW
if (esp_now_init() != ESP_OK) {
Serial.println("Error initializing ESP-NOW");
return;
}
// Register callback function
esp_now_register_recv_cb(OnDataRecv);
pinMode(motorleftPin1, OUTPUT);
pinMode(motorleftPin2, OUTPUT);
pinMode(enableleftPin, OUTPUT);
pinMode(motorrightPin1, OUTPUT);
pinMode(motorrightPin2, OUTPUT);
pinMode(enablerightPin, OUTPUT);
analogWrite(enableleftPin, 255); //full speed
analogWrite(enablerightPin, 255);
}
void loop() {
if (valueX < -200) {
reverse();
} else if (valueX > 200) {
forward();
} else if (valueY < -200) {
right();
} else if (valueY > 200) {
left();
} else {
stop();
}
Serial.println(valueX);
Serial.println(valueY);
delay(500);
}
void left() {
analogWrite(enableleftPin, 255); //full speed
analogWrite(enablerightPin, 255);
digitalWrite(motorleftPin1, HIGH);
digitalWrite(motorleftPin2, LOW);
digitalWrite(motorrightPin1, LOW);
digitalWrite(motorrightPin2, HIGH);
}
void right() {
analogWrite(enableleftPin, 255); //full speed
analogWrite(enablerightPin, 255);
digitalWrite(motorleftPin1, LOW);
digitalWrite(motorleftPin2, HIGH);
digitalWrite(motorrightPin1, HIGH);
digitalWrite(motorrightPin2, LOW);
}
void forward() {
analogWrite(enableleftPin, abs(valueX) / 1.5); //proportional speed
analogWrite(enablerightPin, abs(valueX) / 1.5);
digitalWrite(motorleftPin1, HIGH);
digitalWrite(motorleftPin2, LOW);
digitalWrite(motorrightPin1, HIGH);
digitalWrite(motorrightPin2, LOW);
}
void reverse() {
analogWrite(enableleftPin, 255); //full speed
analogWrite(enablerightPin, 255);
digitalWrite(motorleftPin1, LOW);
digitalWrite(motorleftPin2, HIGH);
digitalWrite(motorrightPin1, LOW);
digitalWrite(motorrightPin2, HIGH);
}
void stop() {
digitalWrite(motorleftPin1, HIGH);
digitalWrite(motorleftPin2, HIGH);
digitalWrite(motorrightPin1, HIGH);
digitalWrite(motorrightPin2, HIGH);
}