#define M_PI 3.14159265359 #if defined(NATIVE) || defined(_WIN32) #include #include #include #include // std::runtime_error #include #include #include #elif defined(TEENSY) #include int BUILTIN_LED = 13; unsigned long last, initTime; #endif #include "Vehicle.h" #include "sim.h" #if defined(NATIVE) || defined(_WIN32) #include "native.h" outVector stateVector; #elif defined(TEENSY) #include "teensy.h" #include const int lc_clock = 23; const int lc_data_0 = 14; const int lc_data_1 = 15; const int lc_data_2 = 19; const int lc_data_3 = 20; void read_lc0(); void read_lc1(); void read_lc2(); void read_lc3(); HX711 lc0; HX711 lc1; HX711 lc2; HX711 lc3; #endif Vehicle State; Vehicle PrevState; #if defined(NATIVE) || defined(_WIN32) void setup() { init_Vehicle(State); // Determine when to burn burnStartTimeCalc(State); } #elif defined(TEENSY) void setup() { Serial.begin(9600); // Configure clock pin with high impedance to protect pin (if this doesn't // work, change to OUTPUT) pinMode(lc_clock, INPUT); // Configure load cell data pins as inputs pinMode(lc_data_0, INPUT); pinMode(lc_data_1, INPUT); pinMode(lc_data_2, INPUT); pinMode(lc_data_3, INPUT); lc0.begin(lc_data_0, lc_clock); lc1.begin(lc_data_1, lc_clock); lc2.begin(lc_data_2, lc_clock); lc3.begin(lc_data_3, lc_clock); // Attach ISRs to load cell data pins to read data when available attachInterrupt(digitalPinToInterrupt(lc_data_0), read_lc0, LOW); attachInterrupt(digitalPinToInterrupt(lc_data_1), read_lc1, LOW); attachInterrupt(digitalPinToInterrupt(lc_data_2), read_lc2, LOW); attachInterrupt(digitalPinToInterrupt(lc_data_3), read_lc3, LOW); Serial.println("Load Cells Initialized"); Serial.print("Calibrating"); lc0.tare(); Serial.print("."); lc1.tare(); Serial.print("."); lc2.tare(); Serial.print("."); lc3.tare(); Serial.println("."); Serial.println("Load Cells Calibrated"); delay(1000); init_Vehicle(State); State.lc0 = lc0.get_value(); State.lc1 = lc1.get_value(); State.lc2 = lc2.get_value(); State.lc3 = lc3.get_value(); Serial.println("Simulated Vehicle Initalized"); delay(1000); // Determine when to burn burnStartTimeCalc(State); Serial.println("Starting Height Calculated"); delay(1000); initFile(); delay(1000); initTime = micros(); } #endif #if defined(NATIVE) || defined(_WIN32) void loop() { vehicleDynamics(State, PrevState); thrustInfo(State); pidController(State, PrevState); TVC(State, PrevState); processTVC(State); state2vec(State, PrevState, stateVector); // Set "prev" values for next timestep PrevState = State; State.time += State.stepSize; if ((State.z < 0.0) && (State.thrustFiring == 2)) { write2CSV(stateVector, State); printSimResults(State); init_Vehicle(State); } } #elif defined(TEENSY) void loop() { last = micros(); Serial.println(State.time); vehicleDynamics(State, PrevState); thrustInfo(State); pidController(State, PrevState); TVC(State, PrevState); processTVC(State); delay(2); State.stepDuration = micros() - last; write2CSV(State); // Set "prev" values for next timestep PrevState = State; // state2vec(State, PrevState, stateVector); State.time += State.stepSize; if ((State.z < 0.0) && (State.thrustFiring == 2)) { Serial.println("Run duration:" + String(micros() - initTime) + " us"); closeFile(); delay(20000); Serial.println("SUCCESS"); Serial.println("Aborting Sim"); teensyAbort(); } delay(20 - ((micros() - last) * 1000.0)); } #endif #if defined(_WIN32) || defined(NATIVE) int main() { setup(); do { loop(); } while ((State.z > 0.0) || (State.thrustFiring != 2)); return 0; } #endif // ISRs to print data to serial monitor void read_lc0() { State.lc0 = lc0.get_value(); } void read_lc1() { State.lc1 = lc1.get_value(); } void read_lc2() { State.lc2 = lc2.get_value(); } void read_lc3() { State.lc3 = lc3.get_value(); }