works
This commit is contained in:
novatic14
2026-03-11 15:43:47 -07:00
parent 7dd1170b71
commit cb5940f54e
14 changed files with 1965 additions and 0 deletions

View File

@@ -0,0 +1,150 @@
/**
* ESP32 Rocket Fin Calibrator (FIXED)
* * MAPPING:
* A -> Servo 27 (UP)
* B -> Servo 14 (DOWN)
* C -> Servo 26 (RIGHT)
* D -> Servo 25 (LEFT)
*/
#include <Arduino.h>
#include <ESP32Servo.h>
// -----------------------------------------------------------
// CONFIGURATION
// -----------------------------------------------------------
const int NUM_SERVOS = 4;
// Pin Definitions
const int PIN_UP = 27;
const int PIN_DOWN = 14;
const int PIN_RIGHT = 26;
const int PIN_LEFT = 25;
// Arrays for easy indexing: 0=UP, 1=DOWN, 2=RIGHT, 3=LEFT
int servoPins[NUM_SERVOS] = {PIN_UP, PIN_DOWN, PIN_RIGHT, PIN_LEFT};
String servoNames[NUM_SERVOS] = {"UP (27)", "DOWN (14)", "RIGHT (26)", "LEFT (25)"};
// This array holds the live center angle for each servo
int centerAngles[NUM_SERVOS] = {90, 90, 90, 90};
// Track which servo is currently selected (Default to 0 / UP)
int activeIndex = 0;
Servo servos[NUM_SERVOS];
// -----------------------------------------------------------
// FUNCTION PROTOTYPES (This fixes the error!)
// -----------------------------------------------------------
void printInstructions();
void printSelection();
void changeAngle(int amount);
// -----------------------------------------------------------
// SETUP
// -----------------------------------------------------------
void setup() {
Serial.begin(115200);
while (!Serial) delay(10);
// Allocate timers
ESP32PWM::allocateTimer(0);
ESP32PWM::allocateTimer(1);
ESP32PWM::allocateTimer(2);
ESP32PWM::allocateTimer(3);
Serial.println("--- Rocket Fin Calibrator Started ---");
// Attach all servos and move to initial 90
for (int i = 0; i < NUM_SERVOS; i++) {
servos[i].setPeriodHertz(50);
servos[i].attach(servoPins[i]);
servos[i].write(centerAngles[i]);
}
printInstructions();
}
// -----------------------------------------------------------
// LOOP
// -----------------------------------------------------------
void loop() {
if (Serial.available() > 0) {
char cmd = Serial.read();
// Ignore newline/carriage return characters
if (cmd == '\n' || cmd == '\r') return;
// Convert lowercase a,b,c,d to uppercase
cmd = toupper(cmd);
// --- SELECTION LOGIC ---
if (cmd == 'A') {
activeIndex = 0;
printSelection();
}
else if (cmd == 'B') {
activeIndex = 1;
printSelection();
}
else if (cmd == 'C') {
activeIndex = 2;
printSelection();
}
else if (cmd == 'D') {
activeIndex = 3;
printSelection();
}
// --- ADJUSTMENT LOGIC ---
else if (cmd == '+') {
changeAngle(1);
}
else if (cmd == '-') {
changeAngle(-1);
}
}
}
// -----------------------------------------------------------
// HELPER FUNCTIONS
// -----------------------------------------------------------
void changeAngle(int amount) {
// Update the angle for the CURRENTLY selected servo only
centerAngles[activeIndex] += amount;
// Safety limits (0 to 180)
if (centerAngles[activeIndex] > 180) centerAngles[activeIndex] = 180;
if (centerAngles[activeIndex] < 0) centerAngles[activeIndex] = 0;
// Move the servo
servos[activeIndex].write(centerAngles[activeIndex]);
// Print Update
Serial.print(">>> Adjusted ");
Serial.print(servoNames[activeIndex]);
Serial.print(" | New Center: ");
Serial.println(centerAngles[activeIndex]);
}
void printSelection() {
Serial.print("\n>>> SELECTED: ");
Serial.println(servoNames[activeIndex]);
Serial.print(" Current Angle: ");
Serial.println(centerAngles[activeIndex]);
Serial.println(" Use '+' or '-' to adjust.");
}
void printInstructions() {
Serial.println("----------------------------------------");
Serial.println("Type 'A' -> Select UP (27)");
Serial.println("Type 'B' -> Select DOWN (14)");
Serial.println("Type 'C' -> Select RIGHT (26)");
Serial.println("Type 'D' -> Select LEFT (25)");
Serial.println("----------------------------------------");
Serial.println("Then use '+' or '-' to adjust that servo.");
Serial.println("----------------------------------------");
// Select A by default on startup
printSelection();
}

View File

@@ -0,0 +1,126 @@
#include <Arduino.h>
#include <Wire.h>
#include <Adafruit_BMP085.h>
#include <QMC5883LCompass.h>
// Initialize sensor objects
Adafruit_BMP085 bmp;
QMC5883LCompass compass;
// Flags and variables
bool bmp_working = false;
const int I2C_SDA = 21;
const int I2C_SCL = 22;
// Function to scan the bus and return number of devices
int scanI2CBus() {
Serial.println("--- Scanning I2C Bus ---");
byte error, address;
int nDevices = 0;
// A standard I2C scanner helps determine if the hardware is electrically connected
for(address = 1; address < 127; address++ ) {
Wire.beginTransmission(address);
error = Wire.endTransmission();
if (error == 0) {
Serial.print("Found device at 0x");
if (address < 16) Serial.print("0");
Serial.print(address, HEX);
// Identify common addresses
if (address == 0x77) Serial.println(" (Likely BMP180)");
else if (address == 0x0D) Serial.println(" (Likely QMC5883L)");
else Serial.println(" (Unknown Device)");
nDevices++;
} else if (error == 4) {
Serial.print("Unknown error at address 0x");
if (address < 16) Serial.print("0");
Serial.println(address, HEX);
}
}
return nDevices;
}
void setup() {
Serial.begin(115200);
delay(2000); // Give serial monitor time to connect
// Initialize I2C with stability settings
// Default for ESP32 DevKit V1 is SDA=21, SCL=22
Wire.begin(I2C_SDA, I2C_SCL);
Wire.setClock(100000); // Standard 100kHz mode is safer for jumper wires
Wire.setTimeOut(1000); // Timeout to prevent the CPU from hanging on a bad bus
int devicesFound = scanI2CBus();
if (devicesFound == 0) {
Serial.println("ERROR: No I2C devices detected!");
Serial.println("1. Check if 3.3V and GND are connected to both sensors.");
Serial.println("2. Check if SDA is on Pin 21 and SCL is on Pin 22.");
Serial.println("3. Ensure your soldering joints are making contact with the pads.");
}
Serial.println("\n--- Initializing Sensor Libraries ---");
// BMP180 Initialization
if (!bmp.begin()) {
Serial.println("BMP180: FAILED to initialize library.");
bmp_working = false;
} else {
Serial.println("BMP180: SUCCESS");
bmp_working = true;
}
// QMC5883L Initialization
compass.init();
compass.setSmoothing(10, true);
Serial.println("QMC5883L: Initialized (Note: init() does not check for presence)");
Serial.println("----------------------------\n");
}
void loop() {
Serial.println("========== SENSOR DATA ==========");
// 1. Process BMP180
if (bmp_working) {
float temp = bmp.readTemperature();
// Check for logical errors (extreme values)
if (temp < -40 || temp > 80) {
Serial.println("[BMP180] Data Error: Reading out of range.");
} else {
Serial.print("[BMP180] Temp: "); Serial.print(temp);
Serial.print(" C | Pressure: "); Serial.print(bmp.readPressure()); Serial.println(" Pa");
}
} else {
Serial.println("[BMP180] OFFLINE (Initialization failed)");
}
// 2. Process QMC5883L
compass.read();
int x = compass.getX();
int y = compass.getY();
int z = compass.getZ();
// If the compass returns all zeros, it is physically disconnected or the bus crashed
if (x == 0 && y == 0 && z == 0) {
Serial.println("[QMC5883L] OFFLINE (Returning all zeros)");
// Attempt emergency bus recovery if we lost communication
Serial.println("Attempting I2C Bus Reset...");
Wire.end();
delay(100);
Wire.begin(I2C_SDA, I2C_SCL);
Wire.setClock(100000);
} else {
Serial.print("[QMC5883L] X: "); Serial.print(x);
Serial.print(" | Y: "); Serial.print(y);
Serial.print(" | Z: "); Serial.print(z);
Serial.print(" | Heading: "); Serial.print(compass.getAzimuth()); Serial.println("°");
}
Serial.println("=================================\n");
delay(1000);
}

View File

@@ -0,0 +1,339 @@
/* =========================================================================
* MPU6050 ROCKET STABILIZATION - ACCESS POINT (AP) VERSION
* =========================================================================
* CHANGES FROM PREVIOUS:
* 1. WiFi Mode: Creates its own WiFi network (SoftAP)
* 2. Addressing: Defaults to BROADCAST IP until it hears from a specific computer
* 3. Discovery: Auto-detects the computer's IP when it receives a command
* 4. PID Tuning: Added runtime PID tuning and saving to internal Flash (NVS)
* ========================================================================= */
#include <Arduino.h>
#include <Wire.h>
#include <Adafruit_MPU6050.h>
#include <Adafruit_Sensor.h>
#include <ESP32Servo.h>
#include <WiFi.h>
#include <WiFiUdp.h>
#include <Preferences.h>
// --- WiFi / Network Configuration ---
// The Rocket will CREATE this network
const char* ssid = "RocketLink_Telemetry";
const char* password = "rocketlaunch";
// Telemetry Destination
// Initially set to BROADCAST so any connected computer can hear it immediately.
// Once a command is received, this updates to the specific sender's IP.
IPAddress remoteIp(192, 168, 4, 255);
const int remotePort = 4444; // Port to send telemetry TO
const int localPort = 4444; // Port to listen for commands ON
WiFiUDP udp;
Preferences preferences;
// --- Hardware Pin Definitions ---
const int LEFT_SERVO_PIN = 26;
const int RIGHT_SERVO_PIN = 25;
const int UP_SERVO_PIN = 27;
const int DOWN_SERVO_PIN = 14;
// --- Servo Settings ---
Servo leftServo;
Servo rightServo;
Servo upServo;
Servo downServo;
const int LEFT_CENTER = 115;
const int RIGHT_CENTER = 80;
const int UP_CENTER = 80;
const int DOWN_CENTER = 115;
const int MAX_DEFLECTION = 15;
// --- PID & Stabilization ---
Adafruit_MPU6050 mpu;
float Kp = 0.5; // Default, overridden by preferences in setup
float Kd = 0.2; // Default, overridden by preferences in setup
float roll = 0;
float gyroX_offset = 0;
// --- State Machine ---
enum RocketState {
STATE_IDLE,
STATE_LAUNCHING,
STATE_FLIGHT
};
RocketState currentState = STATE_IDLE;
// --- Launch Detection Constants ---
const float LAUNCH_THRESHOLD_G = 1.6;
const float G_TO_MS2 = 9.80665;
const float LAUNCH_THRESHOLD_MS2 = LAUNCH_THRESHOLD_G * G_TO_MS2;
const int LAUNCH_DURATION_MS = 50;
unsigned long launchTriggerStartTime = 0;
// --- Timing Variables ---
unsigned long last_time;
float dt;
unsigned long lastStateMsgTime = 0;
const int STATE_MSG_INTERVAL = 2000;
// --- Function Prototypes ---
void setServosEnabled(bool enabled);
void changeState(RocketState newState);
void sendTelemetry(float roll, float rate, int out);
void sendStateUpdate();
void calibrateGyro();
void setup(void) {
Serial.begin(115200);
Wire.begin(21, 22);
// 1. Setup Servos
ESP32PWM::allocateTimer(0);
ESP32PWM::allocateTimer(1);
ESP32PWM::allocateTimer(2);
ESP32PWM::allocateTimer(3);
leftServo.setPeriodHertz(50);
rightServo.setPeriodHertz(50);
upServo.setPeriodHertz(50);
downServo.setPeriodHertz(50);
setServosEnabled(false);
// 2. Setup MPU6050
if (!mpu.begin()) {
Serial.println("Failed to find MPU6050 chip");
while (1) { delay(10); }
}
Serial.println("MPU6050 Found!");
mpu.setAccelerometerRange(MPU6050_RANGE_16_G);
mpu.setGyroRange(MPU6050_RANGE_500_DEG);
mpu.setFilterBandwidth(MPU6050_BAND_21_HZ);
// 3. Load Calibration and PID config
preferences.begin("rocket_cfg", false);
gyroX_offset = preferences.getFloat("gyro_bias", 0.0);
Kp = preferences.getFloat("Kp", 0.5); // Load saved Kp, default to 0.5
Kd = preferences.getFloat("Kd", 0.2); // Load saved Kd, default to 0.2
Serial.println("--- Saved Config Loaded ---");
Serial.print("Gyro Bias: "); Serial.println(gyroX_offset);
Serial.print("Kp: "); Serial.println(Kp);
Serial.print("Kd: "); Serial.println(Kd);
Serial.println("---------------------------");
// 4. Setup Access Point (AP)
Serial.println("Starting Access Point...");
WiFi.softAP(ssid, password);
// The default IP for ESP32 SoftAP is usually 192.168.4.1
Serial.print("AP Created. Connect to: "); Serial.println(ssid);
Serial.print("Rocket IP: "); Serial.println(WiFi.softAPIP());
udp.begin(localPort);
Serial.println("System Ready. Broadcasting Telemetry...");
last_time = millis();
}
void loop() {
sensors_event_t a, g, temp;
mpu.getEvent(&a, &g, &temp);
// Calculate Delta Time
unsigned long current_time = millis();
dt = (current_time - last_time) / 1000.0;
last_time = current_time;
if (dt <= 0) return;
// --- Network: Receive Commands & Auto-Detect Remote IP ---
int packetSize = udp.parsePacket();
if (packetSize) {
// CAPTURE SENDER IP: This enables 2-way comms without hardcoding
IPAddress senderIp = udp.remoteIP();
if (remoteIp != senderIp) {
remoteIp = senderIp;
Serial.print("Connected to Ground Station at: ");
Serial.println(remoteIp);
}
char packetBuffer[255];
int len = udp.read(packetBuffer, 255);
if (len > 0) packetBuffer[len] = 0;
String command = String(packetBuffer);
command.trim();
// -- Parse Tuning Commands (Any state) --
if (command.startsWith("PID,")) {
// Expected format: PID,0.5,0.2
int firstComma = command.indexOf(',');
int secondComma = command.indexOf(',', firstComma + 1);
if (firstComma > 0 && secondComma > 0) {
Kp = command.substring(firstComma + 1, secondComma).toFloat();
Kd = command.substring(secondComma + 1).toFloat();
// Save to internal flash so it survives reboots
preferences.putFloat("Kp", Kp);
preferences.putFloat("Kd", Kd);
Serial.print("New PID Saved -> Kp: "); Serial.print(Kp);
Serial.print(" Kd: "); Serial.println(Kd);
// Send updated state immediately so dashboard syncs
sendStateUpdate();
}
}
// -- Parse Mission Commands (Only in IDLE) --
else if (currentState == STATE_IDLE) {
if (command.equalsIgnoreCase("launch")) {
changeState(STATE_LAUNCHING);
}
else if (command.equalsIgnoreCase("calibrate")) {
Serial.println("Recalibration Command Received.");
calibrateGyro();
roll = 0;
}
}
}
// --- Network: Send State Heartbeat ---
if (millis() - lastStateMsgTime > STATE_MSG_INTERVAL) {
sendStateUpdate();
lastStateMsgTime = millis();
}
// --- Gyro Integration ---
float raw_rate_rad = g.gyro.x - gyroX_offset;
float rate_deg_s = raw_rate_rad * 180.0 / PI;
roll += rate_deg_s * dt;
int currentServoOffset = 0;
// --- STATE MACHINE LOGIC ---
switch (currentState) {
case STATE_IDLE:
break;
case STATE_LAUNCHING:
{
float accel_mag = sqrt(sq(a.acceleration.x) + sq(a.acceleration.y) + sq(a.acceleration.z));
if (accel_mag > LAUNCH_THRESHOLD_MS2) {
if (launchTriggerStartTime == 0) {
launchTriggerStartTime = millis();
} else if (millis() - launchTriggerStartTime > LAUNCH_DURATION_MS) {
changeState(STATE_FLIGHT);
}
} else {
launchTriggerStartTime = 0;
}
}
break;
case STATE_FLIGHT:
{
float P_term = Kp * roll;
float D_term = Kd * rate_deg_s;
float output = P_term + D_term;
currentServoOffset = (int)output;
currentServoOffset = constrain(currentServoOffset, -MAX_DEFLECTION, MAX_DEFLECTION);
leftServo.write(LEFT_CENTER + currentServoOffset);
rightServo.write(RIGHT_CENTER + currentServoOffset);
upServo.write(UP_CENTER + currentServoOffset);
downServo.write(DOWN_CENTER + currentServoOffset);
}
break;
}
// --- TELEMETRY ---
sendTelemetry(roll, rate_deg_s, currentServoOffset);
delay(5);
}
// --- Helper Functions ---
void calibrateGyro() {
Serial.println("Calibrating Gyro... KEEP STILL");
delay(1000);
float sumX = 0;
int calibration_samples = 200;
for (int i = 0; i < calibration_samples; i++) {
sensors_event_t a, g, temp;
mpu.getEvent(&a, &g, &temp);
sumX += g.gyro.x;
delay(5);
}
gyroX_offset = sumX / calibration_samples;
preferences.putFloat("gyro_bias", gyroX_offset);
Serial.print("New Gyro Offset Saved: "); Serial.println(gyroX_offset);
}
void changeState(RocketState newState) {
currentState = newState;
switch (currentState) {
case STATE_IDLE:
setServosEnabled(false);
break;
case STATE_LAUNCHING:
setServosEnabled(false);
launchTriggerStartTime = 0;
roll = 0;
break;
case STATE_FLIGHT:
setServosEnabled(true);
break;
}
sendStateUpdate();
lastStateMsgTime = millis();
}
void setServosEnabled(bool enabled) {
if (enabled) {
if (!leftServo.attached()) leftServo.attach(LEFT_SERVO_PIN, 500, 2400);
if (!rightServo.attached()) rightServo.attach(RIGHT_SERVO_PIN, 500, 2400);
if (!upServo.attached()) upServo.attach(UP_SERVO_PIN, 500, 2400);
if (!downServo.attached()) downServo.attach(DOWN_SERVO_PIN, 500, 2400);
} else {
if (leftServo.attached()) leftServo.detach();
if (rightServo.attached()) rightServo.detach();
if (upServo.attached()) upServo.detach();
if (downServo.attached()) downServo.detach();
}
}
void sendStateUpdate() {
// Send to the current remoteIp (Starts as broadcast .255, then becomes specific)
// Modified to include Kp and Kd so dashboard stays in sync
udp.beginPacket(remoteIp, remotePort);
udp.print("STATUS:");
switch (currentState) {
case STATE_IDLE: udp.print("IDLE"); break;
case STATE_LAUNCHING: udp.print("LAUNCHING"); break;
case STATE_FLIGHT: udp.print("FLIGHT"); break;
}
udp.print(",");
udp.print(Kp);
udp.print(",");
udp.print(Kd);
udp.endPacket();
}
void sendTelemetry(float roll, float rate, int out) {
udp.beginPacket(remoteIp, remotePort);
udp.print("T,");
udp.print(millis());
udp.print(",");
udp.print(roll, 1);
udp.print(",");
udp.print(rate, 1);
udp.print(",");
udp.print(out);
udp.endPacket();
}