mirror of
https://gitlab.com/lander-team/lander-cpp.git
synced 2025-08-02 11:31:34 +00:00
Resolve "Move init_loadCells() to teensy.h"
This commit is contained in:
36
src/main.cpp
36
src/main.cpp
@@ -11,7 +11,6 @@
|
||||
#endif
|
||||
|
||||
#define M_PI 3.14159265359
|
||||
|
||||
#include "Vehicle.h"
|
||||
#include "sim.h"
|
||||
|
||||
@@ -27,23 +26,14 @@ unsigned long last, initTime;
|
||||
#include <HX711.h>
|
||||
#include <PWMServo.h>
|
||||
|
||||
HX711 lc0;
|
||||
HX711 lc1;
|
||||
HX711 lc2;
|
||||
HX711 lc3;
|
||||
|
||||
void read_lc0();
|
||||
void read_lc1();
|
||||
void read_lc2();
|
||||
void read_lc3();
|
||||
|
||||
PWMServo servo1;
|
||||
PWMServo servo2;
|
||||
|
||||
const int pin_servo1 = 33;
|
||||
const int pin_servo2 = 29;
|
||||
const int pin_igniter = 7;
|
||||
|
||||
int servoPos = 0; // variable to store the servo position;
|
||||
int servoPos = 90; // variable to store the servo position;
|
||||
|
||||
void setup() {
|
||||
Serial.begin(9600);
|
||||
@@ -55,12 +45,8 @@ void setup() {
|
||||
delay(1000);
|
||||
}
|
||||
|
||||
init_loadCells(lc0, lc1, lc2, lc3);
|
||||
initLoadCells(State);
|
||||
init_Vehicle(State);
|
||||
State.lc0 = lc0.get_value();
|
||||
State.lc1 = lc1.get_value();
|
||||
State.lc2 = lc2.get_value();
|
||||
State.lc3 = lc3.get_value();
|
||||
|
||||
servo1.attach(pin_servo1);
|
||||
servo2.attach(pin_servo2);
|
||||
@@ -71,11 +57,14 @@ void setup() {
|
||||
Serial.println("Simulated Vehicle Initalized");
|
||||
|
||||
// Determine when to burn
|
||||
analogWrite(pin_igniter, 0);
|
||||
burnStartTimeCalc(State);
|
||||
Serial.println("Starting Height Calculated");
|
||||
|
||||
initFile();
|
||||
|
||||
// PLACE BUTTON HERE---------------------------------------------
|
||||
|
||||
initTime = micros();
|
||||
}
|
||||
|
||||
@@ -88,7 +77,6 @@ void loop() {
|
||||
TVC(State, PrevState);
|
||||
processTVC(State, servo1, servo2);
|
||||
|
||||
State.stepDuration = micros() - last;
|
||||
write2CSV(State);
|
||||
|
||||
// Set previous values for next timestep
|
||||
@@ -96,9 +84,10 @@ void loop() {
|
||||
State.time += State.stepSize;
|
||||
|
||||
if ((State.z < 0.0) && (State.thrustFiring == 2)) {
|
||||
printSimResults(State);
|
||||
analogWrite(pin_igniter, 0);
|
||||
Serial.println("Run duration:" + String((micros() - initTime) / 1000000.0) +
|
||||
" seconds");
|
||||
printSimResults(State);
|
||||
|
||||
closeFile();
|
||||
delay(3000);
|
||||
@@ -108,15 +97,10 @@ void loop() {
|
||||
teensyAbort();
|
||||
}
|
||||
|
||||
delay(State.stepSize - ((micros() - last) / 1000.0));
|
||||
State.stepDuration = micros() - last;
|
||||
delayMicroseconds((1000.0 * State.stepSize) - State.stepDuration);
|
||||
}
|
||||
|
||||
// ISRs to print data to serial monitor - These unfortunately can't move
|
||||
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(); }
|
||||
|
||||
#endif
|
||||
|
||||
#if defined(_WIN32) || defined(NATIVE)
|
||||
|
Reference in New Issue
Block a user