final without sd card
This commit is contained in:
parent
9e25b917f6
commit
f7da4b9885
@ -1,7 +1,9 @@
|
|||||||
#include <SPI.h>
|
#include <SPI.h>
|
||||||
#include <SD.h>
|
#include <SD.h>
|
||||||
#include <Servo.h>
|
#include <Servo.h>
|
||||||
#include "Arduino_BMI270_BMM150.h"
|
#include <Adafruit_MPU6050.h>
|
||||||
|
#include <Adafruit_Sensor.h>
|
||||||
|
#include <Wire.h>
|
||||||
|
|
||||||
const int BUZZER_PIN = 2;
|
const int BUZZER_PIN = 2;
|
||||||
const int SERVO_A_PIN = 7;
|
const int SERVO_A_PIN = 7;
|
||||||
@ -10,10 +12,10 @@ const int CHIP_SELECT = 4;
|
|||||||
// Create objects for modules
|
// Create objects for modules
|
||||||
File dataFile;
|
File dataFile;
|
||||||
Servo A;
|
Servo A;
|
||||||
|
Adafruit_MPU6050 mpu;
|
||||||
|
|
||||||
// Flight stages
|
// Flight stages
|
||||||
enum FlightStage
|
enum FlightStage {
|
||||||
{
|
|
||||||
READY,
|
READY,
|
||||||
ARM,
|
ARM,
|
||||||
ASCENT,
|
ASCENT,
|
||||||
@ -23,14 +25,8 @@ enum FlightStage
|
|||||||
|
|
||||||
FlightStage current_stage = READY;
|
FlightStage current_stage = READY;
|
||||||
|
|
||||||
void setup()
|
void setup() {
|
||||||
{
|
|
||||||
// Initialize Serial
|
|
||||||
Serial.begin(115200);
|
Serial.begin(115200);
|
||||||
|
|
||||||
//while (!Serial)
|
|
||||||
// ;
|
|
||||||
//Serial.println("# Welcome to CobraV2");
|
|
||||||
delay(1000);
|
delay(1000);
|
||||||
|
|
||||||
pinMode(BUZZER_PIN, OUTPUT);
|
pinMode(BUZZER_PIN, OUTPUT);
|
||||||
@ -38,16 +34,23 @@ void setup()
|
|||||||
|
|
||||||
A.attach(SERVO_A_PIN);
|
A.attach(SERVO_A_PIN);
|
||||||
A.write(80);
|
A.write(80);
|
||||||
// Start with preflight stage
|
|
||||||
current_stage = READY;
|
current_stage = READY;
|
||||||
|
|
||||||
|
// Initialize MPU6050
|
||||||
|
if (!mpu.begin()) {
|
||||||
|
Serial.println("Failed to find MPU6050 chip");
|
||||||
|
while (1) delay(10);
|
||||||
|
}
|
||||||
|
|
||||||
|
mpu.setAccelerometerRange(MPU6050_RANGE_16_G);
|
||||||
|
mpu.setGyroRange(MPU6050_RANGE_250_DEG);
|
||||||
|
mpu.setFilterBandwidth(MPU6050_BAND_21_HZ);
|
||||||
|
|
||||||
delay(1000);
|
delay(1000);
|
||||||
}
|
}
|
||||||
|
|
||||||
void loop()
|
void loop() {
|
||||||
{
|
switch (current_stage) {
|
||||||
switch (current_stage)
|
|
||||||
{
|
|
||||||
case READY:
|
case READY:
|
||||||
ready_stage();
|
ready_stage();
|
||||||
break;
|
break;
|
||||||
@ -66,170 +69,88 @@ void loop()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void beep()
|
void beep() {
|
||||||
{
|
|
||||||
digitalWrite(BUZZER_PIN, HIGH);
|
digitalWrite(BUZZER_PIN, HIGH);
|
||||||
delay(1000);
|
delay(1000);
|
||||||
digitalWrite(BUZZER_PIN, LOW);
|
digitalWrite(BUZZER_PIN, LOW);
|
||||||
}
|
}
|
||||||
|
|
||||||
void ready_stage()
|
void ready_stage() {
|
||||||
{
|
|
||||||
Serial.println("# READY stage");
|
Serial.println("# READY stage");
|
||||||
analogWrite(LED_BUILTIN, HIGH);
|
analogWrite(LED_BUILTIN, HIGH);
|
||||||
beep();
|
beep();
|
||||||
|
|
||||||
if (!IMU.begin())
|
Serial.println("# MPU6050 initialized");
|
||||||
{
|
|
||||||
Serial.println("Failed to initialize IMU!");
|
|
||||||
while (1)
|
|
||||||
;
|
|
||||||
}
|
|
||||||
|
|
||||||
// SD card
|
|
||||||
//if (!SD.begin(CHIP_SELECT))
|
|
||||||
//{
|
|
||||||
// Serial.println("# Fail SD module init");
|
|
||||||
//}
|
|
||||||
//else
|
|
||||||
//{
|
|
||||||
// Serial.println("# Success SD module init");
|
|
||||||
//}
|
|
||||||
//
|
|
||||||
//if (SD.exists("data.txt"))
|
|
||||||
//{
|
|
||||||
// Serial.println("# File exists");
|
|
||||||
//}
|
|
||||||
//else
|
|
||||||
//{
|
|
||||||
// Serial.println("# File does not exist");
|
|
||||||
// dataFile = SD.open("data.txt", FILE_WRITE);
|
|
||||||
//}
|
|
||||||
//
|
|
||||||
//if (dataFile)
|
|
||||||
//{
|
|
||||||
// Serial.println("# File opened");
|
|
||||||
// dataFile.println("# CobraV2 flight data");
|
|
||||||
//}
|
|
||||||
//else
|
|
||||||
//{
|
|
||||||
// Serial.println("# Error opening file");
|
|
||||||
//}
|
|
||||||
|
|
||||||
Serial.print("# Accelerometer sample rate = ");
|
|
||||||
Serial.print(IMU.accelerationSampleRate());
|
|
||||||
Serial.println(" Hz");
|
|
||||||
|
|
||||||
//dataFile.print("# Accelerometer sample rate = ");
|
|
||||||
//dataFile.println(IMU.accelerationSampleRate());
|
|
||||||
//dataFile.close();
|
|
||||||
|
|
||||||
current_stage = ARM;
|
current_stage = ARM;
|
||||||
}
|
}
|
||||||
|
|
||||||
void arm_stage()
|
void arm_stage() {
|
||||||
{
|
|
||||||
// System check
|
|
||||||
// Block parachute ejection
|
|
||||||
// Wait for launch pin removed
|
|
||||||
// Start sending data
|
|
||||||
Serial.println("# ARM stage");
|
Serial.println("# ARM stage");
|
||||||
beep();
|
beep();
|
||||||
beep();
|
beep();
|
||||||
|
|
||||||
// Accelerometer Gyroscope
|
|
||||||
int counter = 0;
|
int counter = 0;
|
||||||
float x, y, z;
|
|
||||||
|
|
||||||
bool toggle = false;
|
bool toggle = false;
|
||||||
//dataFile = SD.open("data.txt", FILE_WRITE);
|
sensors_event_t a, g, temp;
|
||||||
//dataFile.println("# ARM stage");
|
|
||||||
while (true)
|
while (true) {
|
||||||
{
|
mpu.getEvent(&a, &g, &temp);
|
||||||
if (IMU.accelerationAvailable())
|
|
||||||
{
|
float x = a.acceleration.x;
|
||||||
IMU.readAcceleration(x, y, z);
|
float y = a.acceleration.y;
|
||||||
Serial.print(x);
|
float z = a.acceleration.z;
|
||||||
Serial.print(", ");
|
|
||||||
Serial.print(y);
|
Serial.print(x); Serial.print(", ");
|
||||||
Serial.print(", ");
|
Serial.print(y); Serial.print(", ");
|
||||||
Serial.println(z);
|
Serial.println(z);
|
||||||
|
|
||||||
|
if (x > 1.0) {
|
||||||
//dataFile.print(x);
|
|
||||||
//dataFile.print(" ");
|
|
||||||
//dataFile.print(y);
|
|
||||||
//dataFile.print(" ");
|
|
||||||
//dataFile.println(z);
|
|
||||||
|
|
||||||
if (x > 1)
|
|
||||||
{
|
|
||||||
Serial.println("# Launch Detect");
|
Serial.println("# Launch Detect");
|
||||||
counter++;
|
counter++;
|
||||||
}
|
} else {
|
||||||
else
|
|
||||||
{
|
|
||||||
counter = 0;
|
counter = 0;
|
||||||
}
|
}
|
||||||
}
|
|
||||||
|
|
||||||
if (counter < 15)
|
if (counter >= 15) {
|
||||||
{
|
|
||||||
Serial.println("# Launching");
|
Serial.println("# Launching");
|
||||||
//dataFile.println("# Launching");
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (toggle)
|
digitalWrite(LED_BUILTIN, toggle ? HIGH : LOW);
|
||||||
{
|
|
||||||
digitalWrite(LED_BUILTIN, HIGH);
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
digitalWrite(LED_BUILTIN, LOW);
|
|
||||||
}
|
|
||||||
toggle = !toggle;
|
toggle = !toggle;
|
||||||
|
delay(10);
|
||||||
}
|
}
|
||||||
|
|
||||||
current_stage = ASCENT;
|
current_stage = ASCENT;
|
||||||
//dataFile.close();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void ascent_stage()
|
void ascent_stage() {
|
||||||
{
|
Serial.println("# ASCENT stage");
|
||||||
Serial.println("# ASCENT Stage");
|
|
||||||
unsigned long StartTime = millis();
|
unsigned long StartTime = millis();
|
||||||
int FailOrientationCounter = 0;
|
|
||||||
//File dataFile = SD.open("data.txt", FILE_WRITE);
|
while (true) {
|
||||||
//dataFile.println("# ASCENT stage");
|
|
||||||
while (true)
|
|
||||||
{
|
|
||||||
unsigned long CurrentTime = millis();
|
unsigned long CurrentTime = millis();
|
||||||
unsigned long ElapsedTime = CurrentTime - StartTime;
|
unsigned long ElapsedTime = CurrentTime - StartTime;
|
||||||
Serial.println(ElapsedTime);
|
Serial.println(ElapsedTime);
|
||||||
|
|
||||||
if (IMU.gyroscopeAvailable())
|
sensors_event_t a, g, temp;
|
||||||
{
|
mpu.getEvent(&a, &g, &temp);
|
||||||
float x, y, z;
|
|
||||||
IMU.readGyroscope(x, y, z);
|
|
||||||
}
|
|
||||||
|
|
||||||
if ((ElapsedTime > 9000))
|
// Add orientation failure logic here if needed
|
||||||
{
|
|
||||||
dataFile.println("# Apogee detected by time");
|
if (ElapsedTime > 9000) {
|
||||||
|
Serial.println("# Apogee detected by time");
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
delay(10);
|
||||||
}
|
}
|
||||||
|
|
||||||
current_stage = DESCENT;
|
current_stage = DESCENT;
|
||||||
//dataFile.close();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void descent_stage()
|
void descent_stage() {
|
||||||
{
|
|
||||||
Serial.println("# DESCENT stage");
|
Serial.println("# DESCENT stage");
|
||||||
//File dataFile = SD.open("data.txt", FILE_WRITE);
|
|
||||||
//dataFile.println("# DESCENT stage");
|
|
||||||
A.write(80);
|
A.write(80);
|
||||||
delay(1000);
|
delay(1000);
|
||||||
A.write(180);
|
A.write(180);
|
||||||
@ -237,25 +158,23 @@ void descent_stage()
|
|||||||
Serial.println("# Parachute deployed");
|
Serial.println("# Parachute deployed");
|
||||||
|
|
||||||
unsigned long StartTime = millis();
|
unsigned long StartTime = millis();
|
||||||
while (true)
|
while (true) {
|
||||||
{
|
|
||||||
unsigned long CurrentTime = millis();
|
unsigned long CurrentTime = millis();
|
||||||
unsigned long ElapsedTime = CurrentTime - StartTime;
|
unsigned long ElapsedTime = CurrentTime - StartTime;
|
||||||
|
|
||||||
if (ElapsedTime > 300000)
|
if (ElapsedTime > 300000) {
|
||||||
{
|
Serial.println("# Landing detected");
|
||||||
//dataFile.println("# Landing detected");
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
|
||||||
current_stage = LANDED;
|
delay(1000);
|
||||||
//dataFile.close();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void landed_stage()
|
current_stage = LANDED;
|
||||||
{
|
}
|
||||||
while (true)
|
|
||||||
{
|
void landed_stage() {
|
||||||
|
while (true) {
|
||||||
Serial.println("# LANDED stage");
|
Serial.println("# LANDED stage");
|
||||||
beep();
|
beep();
|
||||||
delay(200);
|
delay(200);
|
||||||
|
|||||||
Loading…
Reference in New Issue
Block a user