#include <SPI.h>
#include <Wire.h>
#include <RF24.h>
#include <Adafruit_GFX.h>
#include <Adafruit_SSD1306.h>
// NRF24L01 Setup
RF24 radio(4, 5); // CE, CSN
const byte address[6] = "00001";
// Potentiometer Pin
int potPin = 34; // ADC1 input
// OLED Display Setup
#define SCREEN_WIDTH 128
#define SCREEN_HEIGHT 64
#define OLED_RESET -1
Adafruit_SSD1306 display(SCREEN_WIDTH, SCREEN_HEIGHT, &Wire, OLED_RESET);
void setup() {
Serial.begin(115200);
// NRF24L01 Init
radio.begin();
radio.openWritingPipe(address);
radio.setPALevel(RF24_PA_LOW);
radio.setDataRate(RF24_250KBPS);
radio.stopListening();
// OLED Init
if (!display.begin(SSD1306_SWITCHCAPVCC, 0x3C)) {
Serial.println(F("OLED failed"));
while (true); // Freeze if OLED doesn't initialize
}
display.clearDisplay();
display.setTextSize(1);
display.setTextColor(SSD1306_WHITE);
display.setCursor(0, 0);
display.println("Starting...");
display.display();
delay(1000);
}
void loop() {
int potValue = analogRead(potPin); // Range: 0–4095
int throttle = map(potValue, 0, 4095, 1000, 2000); // ESC pulse range
radio.write(&throttle, sizeof(throttle));
// Debug
Serial.print("Pot: ");
Serial.print(potValue);
Serial.print(" => Throttle: ");
Serial.println(throttle);
// OLED Display
display.clearDisplay();
display.setCursor(0, 0);
display.setTextSize(1);
display.println("TX Throttle");
display.setTextSize(1);
display.print("Pot: ");
display.println(potValue);
display.print("PWM: ");
display.println(throttle);
display.display();
delay(20);
}
#include <SPI.h>
#include <Wire.h>
#include <RF24.h>
#include <ESP32Servo.h>
#include <Adafruit_GFX.h>
#include <Adafruit_SSD1306.h>
// NRF24L01 CE, CSN
RF24 radio(4, 5);
const byte address[6] = "00001";
// ESC control
Servo esc;
int escPin = 13;
// OLED Display
#define SCREEN_WIDTH 128
#define SCREEN_HEIGHT 64
#define OLED_RESET -1
Adafruit_SSD1306 display(SCREEN_WIDTH, SCREEN_HEIGHT, &Wire, OLED_RESET);
unsigned long lastSignalTime = 0;
const unsigned long signalTimeout = 1000; // 1 second timeout
void setup() {
Serial.begin(115200);
// ESC setup
esc.attach(escPin, 1000, 2000); // Calibrated ESC range
// NRF24L01 setup
radio.begin();
radio.openReadingPipe(0, address);
radio.setPALevel(RF24_PA_LOW);
radio.setDataRate(RF24_250KBPS);
radio.startListening();
// OLED setup
if (!display.begin(SSD1306_SWITCHCAPVCC, 0x3C)) {
Serial.println(F("OLED failed"));
while (true); // Halt on fail
}
display.clearDisplay();
display.setTextSize(1);
display.setTextColor(SSD1306_WHITE);
display.setCursor(0, 0);
display.println("Waiting for signal...");
display.display();
}
void loop() {
if (radio.available()) {
int throttle;
radio.read(&throttle, sizeof(throttle));
esc.writeMicroseconds(throttle);
Serial.print("Received throttle: ");
Serial.println(throttle);
lastSignalTime = millis();
// Display on OLED
display.clearDisplay();
display.setTextSize(1);
display.setCursor(0, 0);
display.println("Throttle:");
display.setTextSize(2);
display.setCursor(0, 20);
display.print(throttle);
display.println(" us");
display.display();
}
// Optional: Signal timeout failsafe
if (millis() - lastSignalTime > signalTimeout) {
esc.writeMicroseconds(1000); // Cut throttle to min
display.clearDisplay();
display.setTextSize(1);
display.setCursor(0, 0);
display.println("Signal lost!");
display.display();
}
}
updated receiver code
#include <Wire.h>
#include <SPI.h>
#include <RF24.h>
#include <ESP32Servo.h>
#include <Adafruit_GFX.h>
#include <Adafruit_SSD1306.h>
#include <MPU6050.h>
// ---------- NRF24 ----------
RF24 radio(4, 5); // CE, CSN
const byte address[6] = "00001";
// ---------- OLED ----------
Adafruit_SSD1306 display(128, 64, &Wire, -1);
// ---------- MPU6050 ----------
MPU6050 mpu;
float pitch, roll, yaw;
// ---------- RC Channels ----------
struct RCChannels {
uint16_t ch[4]; // [0]=Throttle, [1]=Yaw, [2]=Pitch, [3]=Roll
} channels;
// ---------- ESC Pins & Servo ----------
int motorPins[4] = {13, 12, 14, 27};
Servo esc[4];
// ---------- PID Variables ----------
float targetPitch = 0, targetRoll = 0;
float pitchError, rollError;
float pitchOut, rollOut;
// ---------- PID Constants (Tune These) ----------
float kp = 2.5; // Proportional gain
void setup() {
Serial.begin(115200);
Wire.begin();
// OLED
display.begin(SSD1306_SWITCHCAPVCC, 0x3C);
display.clearDisplay();
display.setTextSize(1);
display.setTextColor(SSD1306_WHITE);
display.setCursor(0, 0);
display.println("FC Init...");
display.display();
// ESCs
for (int i = 0; i < 4; i++) {
esc[i].attach(motorPins[i], 1000, 2000);
}
// NRF24
radio.begin();
radio.setPALevel(RF24_PA_LOW);
radio.setDataRate(RF24_250KBPS);
radio.openReadingPipe(0, address);
radio.startListening();
// MPU6050
mpu.initialize();
if (!mpu.testConnection()) {
display.println("MPU FAIL");
display.display();
while (true);
}
display.println("MPU OK!");
display.display();
delay(1000);
}
void loop() {
// 1. Receive RC input
if (radio.available()) {
radio.read(&channels, sizeof(channels));
}
// 2. Get MPU6050 Data
int16_t ax, ay, az, gx, gy, gz;
mpu.getMotion6(&ax, &ay, &az, &gx, &gy, &gz);
pitch = ay / 16384.0 * 90.0;
roll = ax / 16384.0 * 90.0;
yaw = gz / 131.0;
// 3. Extract RC commands
int throttle = channels.ch[0];
int yawInput = map(channels.ch[1], 1000, 2000, -200, 200);
targetPitch = map(channels.ch[2], 1000, 2000, -20, 20);
targetRoll = map(channels.ch[3], 1000, 2000, -20, 20);
// 4. PID control (P only)
pitchError = targetPitch - pitch;
rollError = targetRoll - roll;
pitchOut = kp * pitchError;
rollOut = kp * rollError;
// 5. Motor mixing with stabilization
int m1 = throttle + pitchOut + rollOut - yawInput; // FL
int m2 = throttle + pitchOut - rollOut + yawInput; // FR
int m3 = throttle - pitchOut - rollOut - yawInput; // BR
int m4 = throttle - pitchOut + rollOut + yawInput; // BL
// 6. Constrain & write
m1 = constrain(m1, 1000, 2000);
m2 = constrain(m2, 1000, 2000);
m3 = constrain(m3, 1000, 2000);
m4 = constrain(m4, 1000, 2000);
esc[0].writeMicroseconds(m1);
esc[1].writeMicroseconds(m2);
esc[2].writeMicroseconds(m3);
esc[3].writeMicroseconds(m4);
// 7. OLED Display
display.clearDisplay();
display.setCursor(0, 0);
display.print("T:"); display.println(throttle);
display.print("P:"); display.print(targetPitch); display.print(" > "); display.println(pitch, 1);
display.print("R:"); display.print(targetRoll); display.print(" > "); display.println(roll, 1);
display.print("Y:"); display.println(yawInput);
display.display();
delay(20);
}
updated transmitter code
#include <Wire.h>
#include <SPI.h>
#include <Adafruit_GFX.h>
#include <Adafruit_SSD1306.h>
#include <RF24.h>
RF24 radio(4, 5); // CE, CSN
const byte address[6] = "00001";
// OLED
#define SCREEN_WIDTH 128
#define SCREEN_HEIGHT 64
Adafruit_SSD1306 display(SCREEN_WIDTH, SCREEN_HEIGHT, &Wire, -1);
// Analog input pins
const int throttlePin = 36; // Potentiometer
const int yawPin = 39; // Joystick 1 (X-axis)
const int pitchPin = 35; // Joystick 2 (Y-axis)
const int rollPin = 32; // Joystick 2 (X-axis)
// Channel data structure
struct RCChannels {
uint16_t ch[4]; // [0] Throttle, [1] Yaw, [2] Pitch, [3] Roll
} channels;
const int JOY_CENTER = 2048;
const int DEAD_ZONE = 100;
void setup() {
Serial.begin(115200);
Wire.begin(21, 22); // ESP32 I2C (SDA, SCL)
// OLED Init
if (!display.begin(SSD1306_SWITCHCAPVCC, 0x3C)) {
Serial.println("OLED not found!");
while (true);
}
display.clearDisplay();
display.setTextSize(1);
display.setTextColor(WHITE);
display.setCursor(0, 0);
display.println("Transmitter Init...");
display.display();
delay(1000);
// NRF24 Init
radio.begin();
radio.setPALevel(RF24_PA_LOW);
radio.setDataRate(RF24_250KBPS);
radio.openWritingPipe(address);
radio.stopListening();
pinMode(throttlePin, INPUT);
pinMode(yawPin, INPUT);
pinMode(pitchPin, INPUT);
pinMode(rollPin, INPUT);
Serial.println("Transmitter Ready!");
}
void loop() {
// Throttle from pot (0 to 100%)
int rawThrottle = analogRead(throttlePin);
channels.ch[0] = map(rawThrottle, 0, 4095, 1000, 2000);
// Joystick channels with center + dead zone
channels.ch[1] = mapJoystick(analogRead(yawPin)); // Yaw
channels.ch[2] = mapJoystick(analogRead(pitchPin)); // Pitch
channels.ch[3] = mapJoystick(analogRead(rollPin)); // Roll
// Send via NRF24
radio.write(&channels, sizeof(channels));
// OLED Output
display.clearDisplay();
display.setCursor(0, 0);
display.print("Thr: "); display.println(channels.ch[0]);
display.print("Yaw: "); display.println(channels.ch[1]);
display.print("Pit: "); display.println(channels.ch[2]);
display.print("Rol: "); display.println(channels.ch[3]);
display.display();
delay(20);
}
// Dead-zone & mapping for centered joysticks
uint16_t mapJoystick(int val) {
int diff = val - JOY_CENTER;
if (abs(diff) < DEAD_ZONE) return 1500;
int mapped = map(diff, -2048, 2047, 1000, 2000);
return constrain(mapped, 1000, 2000);
}
mapped to 100 receiver code
#include <Wire.h>
#include <SPI.h>
#include <RF24.h>
#include <ESP32Servo.h>
#include <Adafruit_GFX.h>
#include <Adafruit_SSD1306.h>
#include <MPU6050.h>
// ---------- NRF24 ----------
RF24 radio(4, 5); // CE, CSN
const byte address[6] = "00001";
// ---------- OLED ----------
Adafruit_SSD1306 display(128, 64, &Wire, -1);
// ---------- MPU6050 ----------
MPU6050 mpu;
float pitch, roll, yaw;
// ---------- RC Channels ----------
struct RCChannels {
uint16_t ch[4]; // [0]=Throttle, [1]=Yaw, [2]=Pitch, [3]=Roll
} channels;
// ---------- ESC Pins & Servo ----------
int motorPins[4] = {13, 12, 14, 27};
Servo esc[4];
// ---------- PID Variables ----------
float targetPitch = 0, targetRoll = 0;
float pitchError, rollError;
float pitchOut, rollOut;
// ---------- PID Constants (Tune These) ----------
float kp = 2.5; // Proportional gain
void setup() {
Serial.begin(115200);
Wire.begin();
// OLED
display.begin(SSD1306_SWITCHCAPVCC, 0x3C);
display.clearDisplay();
display.setTextSize(1);
display.setTextColor(SSD1306_WHITE);
display.setCursor(0, 0);
display.println("FC Init...");
display.display();
// ESCs
for (int i = 0; i < 4; i++) {
esc[i].attach(motorPins[i], 1000, 2000);
}
// NRF24
radio.begin();
radio.setPALevel(RF24_PA_LOW);
radio.setDataRate(RF24_250KBPS);
radio.openReadingPipe(0, address);
radio.startListening();
// MPU6050
mpu.initialize();
if (!mpu.testConnection()) {
display.println("MPU FAIL");
display.display();
while (true);
}
display.println("MPU OK!");
display.display();
delay(1000);
}
void loop() {
// 1. Receive RC input
if (radio.available()) {
radio.read(&channels, sizeof(channels));
}
// 2. Get MPU6050 Data
int16_t ax, ay, az, gx, gy, gz;
mpu.getMotion6(&ax, &ay, &az, &gx, &gy, &gz);
pitch = ay / 16384.0 * 90.0;
roll = ax / 16384.0 * 90.0;
yaw = gz / 131.0;
// 3. Extract RC commands and map them to -100 to +100
int throttle = channels.ch[0]; // Throttle: [1000 to 2000]
int yawInput = map(channels.ch[1], 1000, 2000, -100, 100); // Yaw: [-100 to 100]
targetPitch = map(channels.ch[2], 1000, 2000, -100, 100); // Pitch: [-100 to +100]
targetRoll = map(channels.ch[3], 1000, 2000, -100, 100); // Roll: [-100 to +100]
// 4. PID control (P only)
pitchError = targetPitch - pitch;
rollError = targetRoll - roll;
pitchOut = kp * pitchError;
rollOut = kp * rollError;
// 5. Motor mixing with stabilization
int m1 = throttle + pitchOut + rollOut - yawInput; // FL
int m2 = throttle + pitchOut - rollOut + yawInput; // FR
int m3 = throttle - pitchOut - rollOut - yawInput; // BR
int m4 = throttle - pitchOut + rollOut + yawInput; // BL
// 6. Constrain & write
m1 = constrain(m1, 1000, 2000);
m2 = constrain(m2, 1000, 2000);
m3 = constrain(m3, 1000, 2000);
m4 = constrain(m4, 1000, 2000);
esc[0].writeMicroseconds(m1);
esc[1].writeMicroseconds(m2);
esc[2].writeMicroseconds(m3);
esc[3].writeMicroseconds(m4);
// 7. OLED Display
display.clearDisplay();
display.setCursor(0, 0);
// Display throttle mapped from 1000-2000 to 0-100
int throttlePercent = map(throttle, 1000, 2000, 0, 100);
display.print("Thr: ");
display.println(throttlePercent); // Show throttle as a percentage (0 to 100)
// Display pitch and roll mapped from -100 to +100
display.print("Pit: ");
display.print(targetPitch);
display.print(" > ");
display.println(pitch, 1);
display.print("Rol: ");
display.print(targetRoll);
display.print(" > ");
display.println(roll, 1);
// Display yaw mapped from -100 to +100
display.print("Yaw: ");
display.println(yawInput); // Show yaw as -100 to +100
display.display();
delay(20);
}
mapped transmitter code
#include <Wire.h>
#include <SPI.h>
#include <Adafruit_GFX.h>
#include <Adafruit_SSD1306.h>
#include <RF24.h>
RF24 radio(4, 5); // CE, CSN
const byte address[6] = "00001";
// OLED setup
#define SCREEN_WIDTH 128
#define SCREEN_HEIGHT 64
Adafruit_SSD1306 display(SCREEN_WIDTH, SCREEN_HEIGHT, &Wire, -1);
// Analog input pins
const int throttlePin = 36; // Potentiometer
const int yawPin = 39; // Joystick 1 (X-axis)
const int pitchPin = 35; // Joystick 2 (Y-axis)
const int rollPin = 32; // Joystick 2 (X-axis)
const int JOY_CENTER = 2048;
const int DEAD_ZONE = 100;
// Channel data structure
struct RCChannels {
uint16_t ch[4]; // [0] Throttle, [1] Yaw, [2] Pitch, [3] Roll
} channels;
void setup() {
Serial.begin(115200);
Wire.begin(21, 22); // ESP32 I2C
// OLED Init
if (!display.begin(SSD1306_SWITCHCAPVCC, 0x3C)) {
Serial.println("OLED not found!");
while (true);
}
display.clearDisplay();
display.setTextSize(1);
display.setTextColor(WHITE);
display.setCursor(0, 0);
display.println("Transmitter Init...");
display.display();
delay(1000);
// NRF24 Init
radio.begin();
radio.setPALevel(RF24_PA_LOW);
radio.setDataRate(RF24_250KBPS);
radio.openWritingPipe(address);
radio.stopListening();
pinMode(throttlePin, INPUT);
pinMode(yawPin, INPUT);
pinMode(pitchPin, INPUT);
pinMode(rollPin, INPUT);
Serial.println("Transmitter Ready!");
}
void loop() {
// Throttle 0–100 mapped to 1000–2000
int rawThrottle = analogRead(throttlePin);
int mappedThrottle = map(rawThrottle, 0, 4095, 1000, 2000);
channels.ch[0] = mappedThrottle;
// Joystick values
int yawRaw = analogRead(yawPin);
int pitchRaw = analogRead(pitchPin);
int rollRaw = analogRead(rollPin);
channels.ch[1] = mapJoystick(yawRaw);
channels.ch[2] = mapJoystick(pitchRaw);
channels.ch[3] = mapJoystick(rollRaw);
// Send via NRF24
radio.write(&channels, sizeof(channels));
// Display user-friendly values
display.clearDisplay();
display.setCursor(0, 0);
display.print("Thr: "); display.println(map(channels.ch[0], 1000, 2000, 0, 100));
display.print("Yaw: "); display.println(map(channels.ch[1], 1000, 2000, -100, 100));
display.print("Pit: "); display.println(map(channels.ch[2], 1000, 2000, -100, 100));
display.print("Rol: "); display.println(map(channels.ch[3], 1000, 2000, -100, 100));
display.display();
delay(20);
}
uint16_t mapJoystick(int val) {
int diff = val - JOY_CENTER;
if (abs(diff) < DEAD_ZONE) return 1500; // Centered
int mapped = map(diff, -2048, 2047, 1000, 2000);
return constrain(mapped, 1000, 2000);
}
completely mapped to 100 transmitter
#include <Wire.h>
#include <SPI.h>
#include <Adafruit_GFX.h>
#include <Adafruit_SSD1306.h>
#include <RF24.h>
RF24 radio(4, 5); // CE, CSN
const byte address[6] = "00001";
// OLED
#define SCREEN_WIDTH 128
#define SCREEN_HEIGHT 64
Adafruit_SSD1306 display(SCREEN_WIDTH, SCREEN_HEIGHT, &Wire, -1);
// Analog input pins
const int throttlePin = 36;
const int yawPin = 39;
const int pitchPin = 35;
const int rollPin = 32;
// Channel data structure
struct RCChannels {
uint16_t ch[4]; // [0]=Throttle, [1]=Yaw, [2]=Pitch, [3]=Roll
} channels;
const int DEAD_ZONE = 100;
// Calibrated joystick centers
int joyCenterYaw, joyCenterPitch, joyCenterRoll;
void setup() {
Serial.begin(115200);
Wire.begin(21, 22); // ESP32 I2C
// OLED
display.begin(SSD1306_SWITCHCAPVCC, 0x3C);
display.clearDisplay();
display.setTextSize(1);
display.setTextColor(WHITE);
display.setCursor(0, 0);
display.println("Calibrating...");
display.display();
delay(1000); // Give time to let joystick settle
// Calibrate joystick centers
joyCenterYaw = analogRead(yawPin);
joyCenterPitch = analogRead(pitchPin);
joyCenterRoll = analogRead(rollPin);
display.println("Done");
display.display();
delay(1000);
// NRF24
radio.begin();
radio.setPALevel(RF24_PA_LOW);
radio.setDataRate(RF24_250KBPS);
radio.openWritingPipe(address);
radio.stopListening();
pinMode(throttlePin, INPUT);
pinMode(yawPin, INPUT);
pinMode(pitchPin, INPUT);
pinMode(rollPin, INPUT);
Serial.println("Transmitter Ready!");
}
void loop() {
int rawThrottle = analogRead(throttlePin);
int throttlePct = map(rawThrottle, 0, 4095, 0, 100);
channels.ch[0] = map(throttlePct, 0, 100, 1000, 2000);
int yawMapped = mapJoystick(analogRead(yawPin), joyCenterYaw);
int pitchMapped = mapJoystick(analogRead(pitchPin), joyCenterPitch);
int rollMapped = mapJoystick(analogRead(rollPin), joyCenterRoll);
channels.ch[1] = map(yawMapped, -100, 100, 1000, 2000);
channels.ch[2] = map(pitchMapped, -100, 100, 1000, 2000);
channels.ch[3] = map(rollMapped, -100, 100, 1000, 2000);
radio.write(&channels, sizeof(channels));
display.clearDisplay();
display.setCursor(0, 0);
display.print("Throttle: "); display.println(throttlePct);
display.print("Yaw: "); display.println(yawMapped);
display.print("Pitch: "); display.println(pitchMapped);
display.print("Roll: "); display.println(rollMapped);
display.display();
delay(20);
}
// Dynamic joystick mapping with calibration
int mapJoystick(int val, int center) {
int diff = val - center;
if (abs(diff) < DEAD_ZONE) return 0;
int mapped = map(diff, -2048, 2047, -100, 100);
return constrain(mapped, -100, 100);
}
receiver code with proper axix calibration
#include <Wire.h>
#include <SPI.h>
#include <RF24.h>
#include <ESP32Servo.h>
#include <Adafruit_GFX.h>
#include <Adafruit_SSD1306.h>
#include <MPU6050.h>
// ---------- NRF24 ----------
RF24 radio(4, 5); // CE, CSN
const byte address[6] = "00001";
// ---------- OLED ----------
Adafruit_SSD1306 display(128, 64, &Wire, -1);
// ---------- MPU6050 ----------
MPU6050 mpu;
float pitch, roll, yaw;
// ---------- RC Channels ----------
struct RCChannels {
uint16_t ch[4]; // [0]=Throttle, [1]=Yaw, [2]=Pitch, [3]=Roll
} channels;
// ---------- ESC Pins & Servo ----------
int motorPins[4] = {13, 12, 14, 27};
Servo esc[4];
// ---------- PID Variables ----------
float targetPitch = 0, targetRoll = 0;
float pitchError, rollError;
float pitchOut, rollOut;
// ---------- PID Constants (Tune These) ----------
float kp = 2.5; // Proportional gain
void setup() {
Serial.begin(115200);
Wire.begin();
// OLED
display.begin(SSD1306_SWITCHCAPVCC, 0x3C);
display.clearDisplay();
display.setTextSize(1);
display.setTextColor(SSD1306_WHITE);
display.setCursor(0, 0);
display.println("FC Init...");
display.display();
// ESCs
for (int i = 0; i < 4; i++) {
esc[i].attach(motorPins[i], 1000, 2000);
}
// NRF24
radio.begin();
radio.setPALevel(RF24_PA_LOW);
radio.setDataRate(RF24_250KBPS);
radio.openReadingPipe(0, address);
radio.startListening();
// MPU6050
mpu.initialize();
if (!mpu.testConnection()) {
display.println("MPU FAIL");
display.display();
while (true);
}
display.println("MPU OK!");
display.display();
delay(1000);
}
void loop() {
// 1. Receive RC input
if (radio.available()) {
radio.read(&channels, sizeof(channels));
}
// 2. Get MPU6050 Data
int16_t ax, ay, az, gx, gy, gz;
mpu.getMotion6(&ax, &ay, &az, &gx, &gy, &gz);
pitch = ay / 16384.0 * 90.0;
roll = ax / 16384.0 * 90.0;
yaw = gz / 131.0;
// 3. Extract RC commands and map them to -100 to +100
int throttle = channels.ch[0]; // Throttle: [1000 to 2000]
int yawInput = map(channels.ch[1], 1000, 2000, 100, -100); // Yaw: [-100 to 100]
targetPitch = map(channels.ch[2], 1000, 2000, -100, 100); // Pitch: [-100 to +100]
targetRoll = map(channels.ch[3], 1000, 2000, -100, 100); // Roll: [-100 to +100]
// 4. PID control (P only)
pitchError = targetPitch - pitch;
rollError = targetRoll - roll;
pitchOut = kp * pitchError;
rollOut = kp * rollError;
// 5. Motor mixing with stabilization
int m1 = throttle + pitchOut - rollOut - yawInput; // FL
int m2 = throttle + pitchOut + rollOut + yawInput; // FR
int m3 = throttle - pitchOut + rollOut - yawInput; // BR
int m4 = throttle - pitchOut - rollOut + yawInput; // BL
// 6. Constrain & write
m1 = constrain(m1, 1000, 2000);
m2 = constrain(m2, 1000, 2000);
m3 = constrain(m3, 1000, 2000);
m4 = constrain(m4, 1000, 2000);
esc[0].writeMicroseconds(m1);
esc[1].writeMicroseconds(m2);
esc[2].writeMicroseconds(m3);
esc[3].writeMicroseconds(m4);
// 7. OLED Display
display.clearDisplay();
display.setCursor(0, 0);
// Display throttle mapped from 1000-2000 to 0-100
int throttlePercent = map(throttle, 1000, 2000, 0, 100);
display.print("Thr: ");
display.println(throttlePercent); // Show throttle as a percentage (0 to 100)
// Display pitch and roll mapped from -100 to +100
display.print("Pit: ");
display.print(targetPitch);
display.print(" > ");
display.println(pitch, 1);
display.print("Rol: ");
display.print(targetRoll);
display.print(" > ");
display.println(roll, 1);
// Display yaw mapped from -100 to +100
display.print("Yaw: ");
display.println(yawInput); // Show yaw as -100 to +100
display.display();
delay(20);
}
updated transmitter code lag free
#include <Wire.h>
#include <SPI.h>
#include <Adafruit_GFX.h>
#include <Adafruit_SSD1306.h>
#include <RF24.h>
RF24 radio(4, 5); // CE, CSN
const byte address[6] = "00001";
// OLED
#define SCREEN_WIDTH 128
#define SCREEN_HEIGHT 64
Adafruit_SSD1306 display(SCREEN_WIDTH, SCREEN_HEIGHT, &Wire, -1);
// Analog input pins
const int throttlePin = 36;
const int yawPin = 39;
const int pitchPin = 35;
const int rollPin = 32;
// Channel data structure
struct RCChannels {
uint16_t ch[4]; // [0]=Throttle, [1]=Yaw, [2]=Pitch, [3]=Roll
} channels;
const int DEAD_ZONE = 100;
// Calibrated joystick centers
int joyCenterYaw, joyCenterPitch, joyCenterRoll;
// OLED timing
unsigned long lastOledUpdate = 0;
const unsigned long oledInterval = 100; // update every 100ms
void setup() {
Serial.begin(115200);
Wire.begin(21, 22); // ESP32 I2C
// OLED
display.begin(SSD1306_SWITCHCAPVCC, 0x3C);
display.clearDisplay();
display.setTextSize(1);
display.setTextColor(WHITE);
display.setCursor(0, 0);
display.println("Calibrating...");
display.display();
delay(1000); // Give time for joystick to stabilize
// Calibrate joystick centers
joyCenterYaw = analogRead(yawPin);
joyCenterPitch = analogRead(pitchPin);
joyCenterRoll = analogRead(rollPin);
display.println("Done");
display.display();
delay(1000);
// NRF24
radio.begin();
radio.setPALevel(RF24_PA_LOW);
radio.setDataRate(RF24_250KBPS);
radio.openWritingPipe(address);
radio.stopListening();
pinMode(throttlePin, INPUT);
pinMode(yawPin, INPUT);
pinMode(pitchPin, INPUT);
pinMode(rollPin, INPUT);
Serial.println("Transmitter Ready!");
}
void loop() {
// Read and map throttle (0–100%)
int rawThrottle = analogRead(throttlePin);
int throttlePct = map(rawThrottle, 0, 4095, 0, 100);
channels.ch[0] = map(throttlePct, 0, 100, 1000, 2000);
// Map joystick axes
int yawMapped = mapJoystick(analogRead(yawPin), joyCenterYaw);
int pitchMapped = mapJoystick(analogRead(pitchPin), joyCenterPitch);
int rollMapped = mapJoystick(analogRead(rollPin), joyCenterRoll);
channels.ch[1] = map(yawMapped, -100, 100, 1000, 2000);
channels.ch[2] = map(pitchMapped, -100, 100, 1000, 2000);
channels.ch[3] = map(rollMapped, -100, 100, 1000, 2000);
// Send over NRF
radio.write(&channels, sizeof(channels));
// OLED update (every 100ms)
if (millis() - lastOledUpdate >= oledInterval) {
lastOledUpdate = millis();
display.clearDisplay();
display.setCursor(0, 0);
display.printf("Throttle: %d\n", throttlePct);
display.printf("Yaw: %d\n", yawMapped);
display.printf("Pitch: %d\n", pitchMapped);
display.printf("Roll: %d\n", rollMapped);
display.display();
}
delay(10); // small delay to ease CPU load
}
// Joystick mapping with center calibration
int mapJoystick(int val, int center) {
int diff = val - center;
if (abs(diff) < DEAD_ZONE) return 0;
int mapped = map(diff, -2048, 2047, -100, 100);
return constrain(mapped, -100, 100);
}
armed receiver
#include <Wire.h>
#include <SPI.h>
#include <RF24.h>
#include <ESP32Servo.h>
#include <Adafruit_GFX.h>
#include <Adafruit_SSD1306.h>
#include <MPU6050.h>
// ---------- NRF24 ----------
RF24 radio(4, 5); // CE, CSN
const byte address[6] = "00001";
// ---------- OLED ----------
Adafruit_SSD1306 display(128, 64, &Wire, -1);
// ---------- MPU6050 ----------
MPU6050 mpu;
float pitch, roll, yaw;
// ---------- RC Channels ----------
struct RCChannels {
uint16_t ch[5]; // [0]=Throttle, [1]=Yaw, [2]=Pitch, [3]=Roll, [4]=Arm
} channels;
// ---------- ESC Pins & Servo ----------
int motorPins[4] = {13, 12, 14, 27};
Servo esc[4];
// ---------- PID Variables ----------
float targetPitch = 0, targetRoll = 0;
float pitchError, rollError;
float pitchOut, rollOut;
// ---------- PID Constants (Tune These) ----------
float kp = 2.5; // Proportional gain
bool armed = false; // Track the arming state
void setup() {
Serial.begin(115200);
Wire.begin();
// OLED
display.begin(SSD1306_SWITCHCAPVCC, 0x3C);
display.clearDisplay();
display.setTextSize(1);
display.setTextColor(SSD1306_WHITE);
display.setCursor(0, 0);
display.println("FC Init...");
display.display();
// ESCs
for (int i = 0; i < 4; i++) {
esc[i].attach(motorPins[i], 1000, 2000);
}
// NRF24
radio.begin();
radio.setPALevel(RF24_PA_LOW);
radio.setDataRate(RF24_250KBPS);
radio.openReadingPipe(0, address);
radio.startListening();
// MPU6050
mpu.initialize();
if (!mpu.testConnection()) {
display.println("MPU FAIL");
display.display();
while (true);
}
display.println("MPU OK!");
display.display();
delay(1000);
}
void loop() {
// 1. Receive RC input
if (radio.available()) {
radio.read(&channels, sizeof(channels));
}
// 2. Check for Arming State (Channel 4)
if (channels.ch[4] == 2000) {
armed = true;
} else if (channels.ch[4] == 1000) {
armed = false;
}
// 3. Get MPU6050 Data
int16_t ax, ay, az, gx, gy, gz;
mpu.getMotion6(&ax, &ay, &az, &gx, &gy, &gz);
pitch = ay / 16384.0 * 90.0;
roll = ax / 16384.0 * 90.0;
yaw = gz / 131.0;
// 4. Extract RC commands and map them to -100 to +100
int throttle = channels.ch[0]; // Throttle: [1000 to 2000]
int yawInput = map(channels.ch[1], 1000, 2000, 100, -100); // Yaw: [-100 to 100]
targetPitch = map(channels.ch[2], 1000, 2000, -100, 100); // Pitch: [-100 to +100]
targetRoll = map(channels.ch[3], 1000, 2000, -100, 100); // Roll: [-100 to +100]
// 5. PID control (P only)
pitchError = targetPitch - pitch;
rollError = targetRoll - roll;
pitchOut = kp * pitchError;
rollOut = kp * rollError;
// 6. Motor mixing with stabilization (only if armed)
int m1 = armed ? (throttle + pitchOut - rollOut - yawInput) : 1000; // FL
int m2 = armed ? (throttle + pitchOut + rollOut + yawInput) : 1000; // FR
int m3 = armed ? (throttle - pitchOut + rollOut - yawInput) : 1000; // BR
int m4 = armed ? (throttle - pitchOut - rollOut + yawInput) : 1000; // BL
// 7. Constrain & write
m1 = constrain(m1, 1000, 2000);
m2 = constrain(m2, 1000, 2000);
m3 = constrain(m3, 1000, 2000);
m4 = constrain(m4, 1000, 2000);
esc[0].writeMicroseconds(m1);
esc[1].writeMicroseconds(m2);
esc[2].writeMicroseconds(m3);
esc[3].writeMicroseconds(m4);
// 8. OLED Display
display.clearDisplay();
display.setCursor(0, 0);
// Display throttle mapped from 1000-2000 to 0-100
int throttlePercent = map(throttle, 1000, 2000, 0, 100);
display.print("Thr: ");
display.println(throttlePercent); // Show throttle as a percentage (0 to 100)
// Display pitch and roll mapped from -100 to +100
display.print("Pit: ");
display.print(targetPitch);
display.print(" > ");
display.println(pitch, 1);
display.print("Rol: ");
display.print(targetRoll);
display.print(" > ");
display.println(roll, 1);
// Display yaw mapped from -100 to +100
display.print("Yaw: ");
display.println(yawInput); // Show yaw as -100 to +100
// Display Arming Status
display.print("Status: ");
display.println(armed ? "ARMED" : "DISARMED");
display.display();
delay(20);
}
armed transmitter
#include <Wire.h>
#include <SPI.h>
#include <Adafruit_GFX.h>
#include <Adafruit_SSD1306.h>
#include <RF24.h>
RF24 radio(4, 5); // CE, CSN
const byte address[6] = "00001";
// OLED setup
#define SCREEN_WIDTH 128
#define SCREEN_HEIGHT 64
Adafruit_SSD1306 display(SCREEN_WIDTH, SCREEN_HEIGHT, &Wire, -1);
// Analog input pins
const int throttlePin = 36;
const int yawPin = 39;
const int pitchPin = 35;
const int rollPin = 32;
const int armStickPin = 33; // ✅ Arm/disarm joystick input
// RF channel data
struct RCChannels {
uint16_t ch[5]; // [0]=Throttle, [1]=Yaw, [2]=Pitch, [3]=Roll, [4]=Arm
} channels;
const int DEAD_ZONE = 50;
int joyCenterYaw, joyCenterPitch, joyCenterRoll, joyCenterArm;
bool armed = false;
unsigned long lastOledUpdate = 0;
const unsigned long oledInterval = 100;
void setup() {
Serial.begin(115200);
Wire.begin(21, 22);
display.begin(SSD1306_SWITCHCAPVCC, 0x3C);
display.clearDisplay();
display.setTextSize(1);
display.setTextColor(WHITE);
display.setCursor(0, 0);
display.println("Calibrating...");
display.display();
delay(1000);
// Calibrate joystick centers
joyCenterYaw = analogRead(yawPin);
joyCenterPitch = analogRead(pitchPin);
joyCenterRoll = analogRead(rollPin);
joyCenterArm = analogRead(armStickPin);
display.setCursor(0, 10);
display.println("Calibration Done");
display.display();
delay(1000);
// NRF24 setup
radio.begin();
radio.setPALevel(RF24_PA_LOW);
radio.setDataRate(RF24_250KBPS);
radio.openWritingPipe(address);
radio.stopListening();
pinMode(throttlePin, INPUT);
pinMode(yawPin, INPUT);
pinMode(pitchPin, INPUT);
pinMode(rollPin, INPUT);
pinMode(armStickPin, INPUT); // ✅ used as analog input only
display.clearDisplay();
display.setCursor(0, 0);
display.println("Transmitter Ready");
display.display();
delay(1000);
}
void loop() {
// ✅ Arm/disarm via joystick
int armVal = analogRead(armStickPin);
if (armVal > (joyCenterArm + 800)) {
armed = true;
} else if (armVal < (joyCenterArm - 800)) {
armed = false;
}
// Throttle
int rawThrottle = analogRead(throttlePin);
int throttlePct = map(rawThrottle, 0, 4095, 0, 100);
channels.ch[0] = armed ? map(throttlePct, 0, 100, 1000, 2000) : 1000;
// Map joystick axes
int yawVal = mapJoystick(analogRead(yawPin), joyCenterYaw);
int pitchVal = mapJoystick(analogRead(pitchPin), joyCenterPitch);
int rollVal = mapJoystick(analogRead(rollPin), joyCenterRoll);
channels.ch[1] = map(yawVal, -100, 100, 1000, 2000);
channels.ch[2] = map(pitchVal, -100, 100, 1000, 2000);
channels.ch[3] = map(rollVal, -100, 100, 1000, 2000);
// ✅ Send arming status on ch[4]
channels.ch[4] = armed ? 2000 : 1000;
// Send over NRF24
radio.write(&channels, sizeof(channels));
// OLED update
if (millis() - lastOledUpdate >= oledInterval) {
lastOledUpdate = millis();
display.clearDisplay();
display.setCursor(0, 0);
display.printf("Throttle: %3d\n", throttlePct);
display.printf("Yaw: %4d\n", yawVal);
display.printf("Pitch: %4d\n", pitchVal);
display.printf("Roll: %4d\n", rollVal);
display.printf("Status: %s", armed ? "ARMED" : "DISARMED");
display.display();
}
delay(5);
}
int mapJoystick(int val, int center) {
int diff = val - center;
if (abs(diff) < DEAD_ZONE) return 0;
int mapped;
if (diff > 0) {
mapped = map(diff, 0, 4095 - center, 0, 100);
} else {
mapped = map(diff, -center, 0, -100, 0);
}
return constrain(mapped, -100, 100);
}
esc calibration
#include <Wire.h>
#include <SPI.h>
#include <RF24.h>
#include <ESP32Servo.h>
#include <Adafruit_GFX.h>
#include <Adafruit_SSD1306.h>
// ---------- NRF24 ----------
RF24 radio(4, 5); // CE, CSN
const byte address[6] = "00001";
// ---------- OLED ----------
Adafruit_SSD1306 display(128, 64, &Wire, -1);
// ---------- RC Channels ----------
struct RCChannels {
uint16_t ch[4]; // [0]=Throttle, [1]=Yaw, [2]=Pitch, [3]=Roll
} channels;
// ---------- ESC Pins ----------
int motorPins[4] = {13, 12, 14, 27};
Servo esc[4];
bool calibrationDone = false;
void setup() {
Serial.begin(115200);
Wire.begin();
// OLED
display.begin(SSD1306_SWITCHCAPVCC, 0x3C);
display.clearDisplay();
display.setTextSize(1);
display.setTextColor(SSD1306_WHITE);
display.setCursor(0, 0);
display.println("ESC Cal via TX");
display.display();
// Attach ESCs
for (int i = 0; i < 4; i++) {
esc[i].attach(motorPins[i], 1000, 2000);
}
// NRF24
radio.begin();
radio.setPALevel(RF24_PA_LOW);
radio.setDataRate(RF24_250KBPS);
radio.openReadingPipe(0, address);
radio.startListening();
// --- Wait for throttle at MAX to trigger calibration ---
Serial.println("Set throttle to MAX on transmitter...");
display.println("Hold throttle MAX");
display.display();
// Wait until throttle input from TX is >1900
while (!radio.available()) delay(10);
while (true) {
radio.read(&channels, sizeof(channels));
if (channels.ch[0] > 1900) break;
delay(10);
}
Serial.println("MAX throttle detected. Calibrating...");
display.println("MAX detected...");
display.display();
// Send max signal to ESCs
for (int i = 0; i < 4; i++) {
esc[i].writeMicroseconds(2000);
}
delay(4000); // Wait for ESCs to register max
// Now wait for throttle MIN
Serial.println("Set throttle to MIN...");
display.println("Set throttle MIN");
display.display();
while (true) {
if (radio.available()) {
radio.read(&channels, sizeof(channels));
if (channels.ch[0] < 1100) break;
}
delay(10);
}
Serial.println("MIN throttle detected. Finishing calibration...");
display.println("MIN detected...");
display.display();
// Send min signal to ESCs
for (int i = 0; i < 4; i++) {
esc[i].writeMicroseconds(1000);
}
delay(3000); // Wait for ESCs to beep
Serial.println("ESC Calibration Done!");
display.clearDisplay();
display.setCursor(0, 0);
display.println("ESC Cal Done!");
display.display();
delay(2000);
}
void loop() {
// Normal receiver behavior after calibration
if (radio.available()) {
radio.read(&channels, sizeof(channels));
int throttle = channels.ch[0];
int yawInput = map(channels.ch[1], 1000, 2000, 100, -100);
int pitch = map(channels.ch[2], 1000, 2000, -100, 100);
int roll = map(channels.ch[3], 1000, 2000, -100, 100);
// Send throttle directly (no stabilization)
int m1 = constrain(throttle, 1000, 2000);
int m2 = m1, m3 = m1, m4 = m1;
esc[0].writeMicroseconds(m1);
esc[1].writeMicroseconds(m2);
esc[2].writeMicroseconds(m3);
esc[3].writeMicroseconds(m4);
display.clearDisplay();
display.setCursor(0, 0);
display.printf("Throttle: %d\n", map(throttle, 1000, 2000, 0, 100));
display.display();
}
delay(20);
}