mirror of
https://gitlab.com/lander-team/lander-cpp.git
synced 2025-06-16 07:06:51 +00:00
Merge branch '15-integrate-with-sd-card' into 'main'
Resolve "Integrate with SD Card" Closes #15 See merge request lander-team/lander-cpp!20
This commit is contained in:
commit
995d856d08
8
.vscode/extensions.json
vendored
8
.vscode/extensions.json
vendored
@ -1,8 +1,10 @@
|
|||||||
{
|
{
|
||||||
|
// See http://go.microsoft.com/fwlink/?LinkId=827846
|
||||||
|
// for the documentation about the extensions.json format
|
||||||
"recommendations": [
|
"recommendations": [
|
||||||
"ms-vscode.cpptools",
|
"ms-vscode.cpptools",
|
||||||
"wayou.vscode-todo-highlight",
|
"platformio.platformio-ide",
|
||||||
"usernamehw.errorlens",
|
"usernamehw.errorlens",
|
||||||
"platformio.platformio-ide"
|
"wayou.vscode-todo-highlight"
|
||||||
]
|
]
|
||||||
}
|
}
|
||||||
|
@ -117,6 +117,10 @@ void write2CSV(outVector &stateVector, Vehicle &State) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
void printSimResults(Vehicle &State) {
|
void printSimResults(Vehicle &State) {
|
||||||
|
State.yaw = State.yaw * 180 / M_PI;
|
||||||
|
State.pitch = State.pitch * 180 / M_PI;
|
||||||
|
State.roll = State.roll * 180 / M_PI;
|
||||||
|
|
||||||
double landing_angle =
|
double landing_angle =
|
||||||
pow(State.yaw * State.yaw + State.pitch * State.pitch, .5);
|
pow(State.yaw * State.yaw + State.pitch * State.pitch, .5);
|
||||||
|
|
||||||
|
@ -4,11 +4,7 @@
|
|||||||
#define OUTVECTOR_H
|
#define OUTVECTOR_H
|
||||||
|
|
||||||
struct outVector {
|
struct outVector {
|
||||||
#if defined(NATIVE) || defined(_WIN32)
|
int length = 10000; // current sim runs ~5000 steps, x2 just in case
|
||||||
int length = 100000; // current sim runs ~5000 steps, x2 just in case
|
|
||||||
#elif defined(TEENSY)
|
|
||||||
int length = 1000; // current sim runs ~5000 steps, x2 just in case
|
|
||||||
#endif
|
|
||||||
|
|
||||||
std::vector<double> x = std::vector<double>(length, 0.0);
|
std::vector<double> x = std::vector<double>(length, 0.0);
|
||||||
std::vector<double> y = std::vector<double>(length, 0.0);
|
std::vector<double> y = std::vector<double>(length, 0.0);
|
||||||
|
@ -235,9 +235,6 @@ void state2vec(Vehicle &State, Vehicle &PrevState, outVector &stateVector) {
|
|||||||
stateVector.PIDy[t] = State.PIDy;
|
stateVector.PIDy[t] = State.PIDy;
|
||||||
|
|
||||||
stateVector.thrust[t] = State.thrust;
|
stateVector.thrust[t] = State.thrust;
|
||||||
|
|
||||||
// Set "prev" values for next timestep
|
|
||||||
PrevState = State;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
double derivative(double current, double previous, double step) {
|
double derivative(double current, double previous, double step) {
|
||||||
|
120
include/teensy.h
120
include/teensy.h
@ -1,13 +1,19 @@
|
|||||||
#include "Vehicle.h"
|
#include "Vehicle.h"
|
||||||
|
|
||||||
#include <Arduino.h>
|
#include <Arduino.h>
|
||||||
|
#include <SD.h>
|
||||||
void thrustInfo(struct Vehicle &);
|
#include <SPI.h>
|
||||||
void processTVC(struct Vehicle &);
|
|
||||||
void write2CSV(struct outVector &, struct Vehicle &);
|
|
||||||
void printSimResults(struct Vehicle &);
|
|
||||||
|
|
||||||
double loadCellCalibrate();
|
double loadCellCalibrate();
|
||||||
|
void initFile();
|
||||||
|
void thrustInfo(struct Vehicle &);
|
||||||
|
void processTVC(struct Vehicle &);
|
||||||
|
void write2CSV(struct Vehicle &);
|
||||||
|
void printSimResults(struct Vehicle &);
|
||||||
|
void teensyAbort();
|
||||||
|
|
||||||
|
const int chipSelect = BUILTIN_SDCARD;
|
||||||
|
File dataFile;
|
||||||
|
|
||||||
double loadCellCalibrate() {
|
double loadCellCalibrate() {
|
||||||
// place code to calibrate load cells in here
|
// place code to calibrate load cells in here
|
||||||
@ -19,6 +25,38 @@ double loadCellCalibrate() {
|
|||||||
return loadTotal / 10;
|
return loadTotal / 10;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void initFile() {
|
||||||
|
Serial.print("Initializing SD card...");
|
||||||
|
|
||||||
|
// see if the card is present and can be initialized:
|
||||||
|
if (!SD.begin(chipSelect)) {
|
||||||
|
Serial.println("Card failed, or not present. \n\nABORTING SIMULATION");
|
||||||
|
teensyAbort();
|
||||||
|
}
|
||||||
|
Serial.println("Card initialized.");
|
||||||
|
|
||||||
|
// Delete any previous existing files
|
||||||
|
if (SD.exists("simOut.csv")) {
|
||||||
|
SD.remove("simOut.csv");
|
||||||
|
}
|
||||||
|
|
||||||
|
// Open simOut.csv
|
||||||
|
dataFile = SD.open("simOut.csv", FILE_WRITE);
|
||||||
|
if (dataFile) {
|
||||||
|
Serial.println("File successfully opened!");
|
||||||
|
|
||||||
|
} else {
|
||||||
|
// if the file didn't open, print an error:
|
||||||
|
Serial.println("Error opening simOut.csv. \n\nABORTING SIMULATION");
|
||||||
|
teensyAbort();
|
||||||
|
}
|
||||||
|
|
||||||
|
// File Header
|
||||||
|
dataFile.println(
|
||||||
|
"t,x,y,z,vx,vy,vz,ax,ay,az,yaw,pitch,roll,yawdot,pitchdot,rolldot,"
|
||||||
|
"Servo1,Servo2,thrustFiring,PIDx,PIDy,thrust");
|
||||||
|
}
|
||||||
|
|
||||||
void thrustInfo(Vehicle &State) {
|
void thrustInfo(Vehicle &State) {
|
||||||
if (State.time == 0) {
|
if (State.time == 0) {
|
||||||
Serial.println("WARNING: thrustInfo not implemented for TEENSY");
|
Serial.println("WARNING: thrustInfo not implemented for TEENSY");
|
||||||
@ -78,12 +116,67 @@ void processTVC(Vehicle &State) {
|
|||||||
State.momentZ = 0;
|
State.momentZ = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
void write2CSV(outVector &stateVector, Vehicle &State) {
|
void write2CSV(Vehicle &State) {
|
||||||
|
dataFile.print(State.time);
|
||||||
|
dataFile.print(",");
|
||||||
|
|
||||||
Serial.println("WARNING: write2CSV not implemented for TEENSY");
|
dataFile.print(State.x);
|
||||||
|
dataFile.print(",");
|
||||||
|
dataFile.print(State.y);
|
||||||
|
dataFile.print(",");
|
||||||
|
dataFile.print(State.z);
|
||||||
|
dataFile.print(",");
|
||||||
|
|
||||||
|
dataFile.print(State.vx);
|
||||||
|
dataFile.print(",");
|
||||||
|
dataFile.print(State.vy);
|
||||||
|
dataFile.print(",");
|
||||||
|
dataFile.print(State.vz);
|
||||||
|
dataFile.print(",");
|
||||||
|
|
||||||
|
dataFile.print(State.ax);
|
||||||
|
dataFile.print(",");
|
||||||
|
dataFile.print(State.ay);
|
||||||
|
dataFile.print(",");
|
||||||
|
dataFile.print(State.az);
|
||||||
|
dataFile.print(",");
|
||||||
|
|
||||||
|
dataFile.print(State.yaw * 180 / M_PI);
|
||||||
|
dataFile.print(",");
|
||||||
|
dataFile.print(State.pitch * 180 / M_PI);
|
||||||
|
dataFile.print(",");
|
||||||
|
dataFile.print(State.roll * 180 / M_PI);
|
||||||
|
dataFile.print(",");
|
||||||
|
|
||||||
|
dataFile.print(State.yawdot * 180 / M_PI);
|
||||||
|
dataFile.print(",");
|
||||||
|
dataFile.print(State.pitchdot * 180 / M_PI);
|
||||||
|
dataFile.print(",");
|
||||||
|
dataFile.print(State.rolldot * 180 / M_PI);
|
||||||
|
dataFile.print(",");
|
||||||
|
|
||||||
|
dataFile.print(State.xServoDegs);
|
||||||
|
dataFile.print(",");
|
||||||
|
dataFile.print(State.yServoDegs);
|
||||||
|
dataFile.print(",");
|
||||||
|
|
||||||
|
dataFile.print(State.thrustFiring);
|
||||||
|
dataFile.print(",");
|
||||||
|
|
||||||
|
dataFile.print(State.PIDx);
|
||||||
|
dataFile.print(",");
|
||||||
|
dataFile.print(State.PIDy);
|
||||||
|
dataFile.print(",");
|
||||||
|
|
||||||
|
dataFile.print(State.thrust);
|
||||||
|
dataFile.print("\n");
|
||||||
}
|
}
|
||||||
|
|
||||||
void printSimResults(Vehicle &State) {
|
void printSimResults(Vehicle &State) {
|
||||||
|
State.yaw = State.yaw * 180 / M_PI;
|
||||||
|
State.pitch = State.pitch * 180 / M_PI;
|
||||||
|
State.roll = State.roll * 180 / M_PI;
|
||||||
|
|
||||||
double landing_angle =
|
double landing_angle =
|
||||||
pow(State.yaw * State.yaw + State.pitch * State.pitch, .5);
|
pow(State.yaw * State.yaw + State.pitch * State.pitch, .5);
|
||||||
|
|
||||||
@ -106,5 +199,16 @@ void printSimResults(Vehicle &State) {
|
|||||||
Serial.print("Final Velocity: [" + String(State.vx) + ", " +
|
Serial.print("Final Velocity: [" + String(State.vx) + ", " +
|
||||||
String(State.vy) + ", " + String(State.vz) + "]\n");
|
String(State.vy) + ", " + String(State.vz) + "]\n");
|
||||||
|
|
||||||
Serial.print("\n\nSimulation Complete\n");
|
Serial.print("\nSimulation Complete\n");
|
||||||
|
}
|
||||||
|
|
||||||
|
void closeFile() {
|
||||||
|
// close the file:
|
||||||
|
dataFile.close();
|
||||||
|
Serial.println("File closed\n");
|
||||||
|
}
|
||||||
|
|
||||||
|
void teensyAbort() {
|
||||||
|
while (1) {
|
||||||
|
}
|
||||||
}
|
}
|
23
src/main.cpp
23
src/main.cpp
@ -19,13 +19,13 @@ unsigned long last;
|
|||||||
|
|
||||||
#if defined(NATIVE) || defined(_WIN32)
|
#if defined(NATIVE) || defined(_WIN32)
|
||||||
#include "native.h"
|
#include "native.h"
|
||||||
|
outVector stateVector;
|
||||||
#elif defined(TEENSY)
|
#elif defined(TEENSY)
|
||||||
#include "teensy.h"
|
#include "teensy.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
Vehicle State;
|
Vehicle State;
|
||||||
Vehicle PrevState;
|
Vehicle PrevState;
|
||||||
outVector stateVector;
|
|
||||||
|
|
||||||
#if defined(NATIVE) || defined(_WIN32)
|
#if defined(NATIVE) || defined(_WIN32)
|
||||||
void setup() {
|
void setup() {
|
||||||
@ -48,6 +48,8 @@ void setup() {
|
|||||||
loadCellCalibrate();
|
loadCellCalibrate();
|
||||||
Serial.println("Load Cells Calibrated");
|
Serial.println("Load Cells Calibrated");
|
||||||
delay(1000);
|
delay(1000);
|
||||||
|
initFile();
|
||||||
|
delay(1000);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@ -60,6 +62,9 @@ void loop() {
|
|||||||
processTVC(State);
|
processTVC(State);
|
||||||
state2vec(State, PrevState, stateVector);
|
state2vec(State, PrevState, stateVector);
|
||||||
|
|
||||||
|
// Set "prev" values for next timestep
|
||||||
|
PrevState = State;
|
||||||
|
|
||||||
State.time += State.stepSize;
|
State.time += State.stepSize;
|
||||||
|
|
||||||
if (State.z < 0.0) {
|
if (State.z < 0.0) {
|
||||||
@ -70,24 +75,32 @@ void loop() {
|
|||||||
}
|
}
|
||||||
#elif defined(TEENSY)
|
#elif defined(TEENSY)
|
||||||
void loop() {
|
void loop() {
|
||||||
|
|
||||||
last = millis();
|
last = millis();
|
||||||
vehicleDynamics(State, PrevState);
|
vehicleDynamics(State, PrevState);
|
||||||
thrustInfo(State);
|
thrustInfo(State);
|
||||||
pidController(State, PrevState);
|
pidController(State, PrevState);
|
||||||
TVC(State, PrevState);
|
TVC(State, PrevState);
|
||||||
processTVC(State);
|
processTVC(State);
|
||||||
// state2vec(State, PrevState, stateVector);
|
write2CSV(State);
|
||||||
|
|
||||||
|
// Set "prev" values for next timestep
|
||||||
|
PrevState = State;
|
||||||
|
|
||||||
State.time += State.stepSize;
|
State.time += State.stepSize;
|
||||||
|
|
||||||
if (State.z < 0.0) {
|
if (State.z < 0.0) {
|
||||||
write2CSV(stateVector, State);
|
|
||||||
printSimResults(State);
|
printSimResults(State);
|
||||||
init_Vehicle(State);
|
init_Vehicle(State);
|
||||||
Serial.println("Last run duration:" + String(millis() - last + " ms"));
|
|
||||||
|
|
||||||
delay(1000);
|
delay(1000);
|
||||||
|
Serial.println("Last run duration:" + String(millis() - last) + " ms");
|
||||||
|
|
||||||
|
closeFile();
|
||||||
|
delay(10000);
|
||||||
|
|
||||||
Serial.println("Restarting Sim");
|
Serial.println("Restarting Sim");
|
||||||
|
Serial.println(
|
||||||
|
"===============================================================");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
Loading…
x
Reference in New Issue
Block a user