Transmitter which is mega2560.
Which have following.
- JOYSTICK2
2.3BUTTONS
3.1*POT
4.Reprap graphics display smart controller.
code can control:
Throttle (speed or power output)
Yaw (left-right rotation)
Pitch (up-down tilt)
Roll (side-to-side tilt)
AUX1 (additional control, often used for special functions)
AUX2 (another auxiliary control, potentially multi-state)
control a radio-controlled (RC) model vehicle or aircraft. It uses an Arduino Mega with an NRF24L01 radio module to receive control data wirelessly. The received data includes throttle, yaw, pitch, roll, and auxiliary controls (AUX1 and AUX2). These control inputs are read from analog joysticks, potentiometers, and buttons connected to the Arduino.
The code generates a Pulse Position Modulation (PPM) signal on pin 11 of the Arduino Mega, which is typically used to control RC servos or ESCs (Electronic Speed Controllers). This PPM signal encodes the control data into timed pulses, allowing precise control over the model's movements or actions.
In summary, the code facilitates wireless control of an RC model vehicle or aircraft by receiving control inputs via NRF24L01 radio module and generating a PPM signal to control servos or ESCs based on the received data.
#include <SPI.h>
#include <nRF24L01.h>
#include <RF24.h>
#include <Wire.h>
#include <U8g2lib.h>
// PPM CONFIGURATION
#define CHANNEL_NUMBER 6 // Number of channels
#define SIG_PIN 11 // PPM signal output pin on Arduino Mega 2560
#define PPM_FRAME_LENGTH 27000 // PPM frame length in microseconds
#define PPM_PULSE_LENGTH 400 // Pulse length
// Initialize the display
#define SCREEN_WIDTH 128 // Display width, in pixels
#define SCREEN_HEIGHT 64 // Display height, in pixels
U8G2_ST7565_128X64_NONAME_F_HW_I2C display(U8G2_R0);
// Radio module setup
RF24 radio(48, 49); // CE, CSN pins on Arduino Mega 2560
const uint64_t PIPE_IN1 = 0xE8E8F0F0E1LL; // Address for the first nRF24L01+ module
const uint8_t PA_LEVEL = RF24_PA_HIGH; // Power Amplifier level
// Data structure for communication
struct MyData {
byte throttle;
byte yaw;
byte pitch;
byte roll;
byte AUX1;
byte AUX2;
};
MyData data;
// Pins for joystick, potentiometer, and buttons
const int JOY1_X_PIN = A0;
const int JOY1_Y_PIN = A1;
const int JOY2_X_PIN = A2;
const int JOY2_Y_PIN = A3;
const int POT_PIN = A4;
const int BUTTON1_PIN = 4;
const int BUTTON2_PIN = 5;
const int BUTTON3_PIN = 6;
// Voltage sensor pin
const int VOLTAGE_PIN = A5; // Analog pin for voltage sensor
// PPM signal array
int ppm[CHANNEL_NUMBER];
// Variables for PPM signal generation
volatile boolean ppmState = false;
volatile byte ppmChannel = 0;
volatile unsigned int ppmRest = 0;
/**************************************************/
float readVoltage() {
int sensorValue = analogRead(VOLTAGE_PIN);
float voltage = sensorValue * (5.0 / 1023.0); // Assuming a 5V reference
return voltage;
}
void resetData() {
// Reset data to safe values
data.throttle = 0;
data.yaw = 127;
data.pitch = 127;
data.roll = 127;
data.AUX1 = 0;
data.AUX2 = 0;
setPPMValuesFromData();
}
void setPPMValuesFromData() {
// Map data values to PPM range
ppm[0] = map(data.throttle, 0, 255, 1000, 2000);
ppm[1] = map(data.yaw, 0, 255, 1000, 2000);
ppm[2] = map(data.pitch, 0, 255, 1000, 2000);
ppm[3] = map(data.roll, 0, 255, 1000, 2000);
ppm[4] = map(data.AUX1, 0, 1, 1000, 2000); // Assuming AUX1 is boolean (0 or 1)
ppm[5] = map(data.AUX2, 0, 1, 1000, 2000); // Assuming AUX2 is boolean (0 or 1)
}
/**************************************************/
void setupPPM() {
// Initialize PPM signal generation
pinMode(SIG_PIN, OUTPUT);
digitalWrite(SIG_PIN, LOW);
cli(); // Disable interrupts
// Configure Timer1 for PPM generation
TCCR1A = 0;
TCCR1B = 0;
OCR1A = 100; // Compare match register
TCCR1B |= (1 << WGM12); // CTC mode
TCCR1B |= (1 << CS11); // Prescaler 8: 0.5 microseconds at 16MHz
TIMSK1 |= (1 << OCIE1A); // Enable timer compare interrupt
sei(); // Enable interrupts
}
/**************************************************/
void setupDisplay() {
// Initialize the display
display.begin();
display.setContrast(255); // Adjust contrast if necessary
}
/**************************************************/
void setup() {
// Initialize serial communication
Serial.begin(9600);
// Initialize PPM and display
resetData();
setupPPM();
setupDisplay();
// Setup radio module
radio.begin();
radio.setDataRate(RF24_250KBPS);
radio.setPALevel(PA_LEVEL);
radio.setAutoAck(false);
radio.openReadingPipe(1, PIPE_IN1);
radio.startListening();
// Initialize button pins
pinMode(BUTTON1_PIN, INPUT);
pinMode(BUTTON2_PIN, INPUT);
pinMode(BUTTON3_PIN, INPUT);
}
/**************************************************/
unsigned long lastRecvTime = 0;
void recvData() {
// Receive data from radio
while (radio.available()) {
radio.read(&data, sizeof(MyData));
lastRecvTime = millis();
}
}
/**************************************************/
void updateDisplay() {
float voltage = readVoltage(); // Get the voltage
display.clearBuffer();
display.setFont(u8g2_font_ncenB08_tr); // Choose a font
display.setCursor(0, 10);
display.print("Throttle: ");
display.println(data.throttle);
display.print("Yaw: ");
display.println(data.yaw);
display.print("Pitch: ");
display.println(data.pitch);
display.print("Roll: ");
display.println(data.roll);
display.print("AUX1: ");
display.println(data.AUX1);
display.print("AUX2: ");
display.println(data.AUX2);
display.print("Voltage: ");
display.print(voltage, 2); // Print voltage with 2 decimal places
display.println(" V");
display.sendBuffer();
}
/**************************************************/
void loop() {
recvData();
unsigned long now = millis();
if (now - lastRecvTime > 1000) {
// Signal lost, reset data to default
resetData();
}
// Read joystick and sensor values
data.throttle = map(analogRead(JOY1_Y_PIN), 0, 1023, 0, 255);
data.yaw = map(analogRead(JOY1_X_PIN), 0, 1023, 0, 255);
data.pitch = map(analogRead(JOY2_Y_PIN), 0, 1023, 0, 255);
data.roll = map(analogRead(JOY2_X_PIN), 0, 1023, 0, 255);
data.AUX1 = map(analogRead(POT_PIN), 0, 1023, 0, 255) > 512 ? 1 : 0;
// Read button states
if (digitalRead(BUTTON1_PIN) == HIGH) {
data.AUX2 = 1;
} else if (digitalRead(BUTTON2_PIN) == HIGH) {
data.AUX2 = 2;
} else if (digitalRead(BUTTON3_PIN) == HIGH) {
data.AUX2 = 3;
} else {
data.AUX2 = 0;
}
// Update PPM values and display
setPPMValuesFromData();
updateDisplay(); // Ensure display is updated
}
/**************************************************/
ISR(TIMER1_COMPA_vect) {
// PPM signal generation interrupt
if (ppmState) {
digitalWrite(SIG_PIN, LOW); // End pulse
OCR1A = PPM_PULSE_LENGTH * 2; // PPM_PULSE_LENGTH * clockMultiplier
ppmState = false;
} else {
if (ppmChannel >= CHANNEL_NUMBER) {
ppmChannel = 0;
ppmRest += PPM_PULSE_LENGTH;
OCR1A = (PPM_FRAME_LENGTH - ppmRest) * 2; // (PPM_FRAME_LENGTH - calc_rest) * clockMultiplier
ppmRest = 0;
} else {
digitalWrite(SIG_PIN, HIGH); // Start pulse
ppmState = true;
OCR1A = (ppm[ppmChannel] - PPM
OCR1A = (ppm[ppmChannel] - PPM_PULSE_LENGTH) * 2; // (ppm[cur_chan_numb] - PPM_PulseLen) * clockMultiplier
ppmRest += ppm[ppmChannel];
ppmChannel++;
}
}
}