1
0
mirror of https://gitlab.com/lander-team/lander-cpp.git synced 2025-06-16 07:06:51 +00:00

new load cell gains, conditions for ignition while loop

This commit is contained in:
bpmcgeeney 2021-11-30 13:14:12 -07:00
parent c30984600d
commit 1e4fbe8b20
2 changed files with 27 additions and 10 deletions

View File

@ -35,10 +35,10 @@ const int pin_lc2 = 19; // White
const int pin_lc3 = 20; // Black
const int pin_igniter = 7;
double lcGain0 = -107.39;
double lcGain1 = -107.39;
double lcGain2 = -107.39;
double lcGain3 = -107.39;
double lcGain0 = -300.72;
double lcGain1 = -367.5;
double lcGain2 = -565.78;
double lcGain3 = -505.02;
// SD card stuff
const int chipSelect = BUILTIN_SDCARD;
@ -238,10 +238,13 @@ void thrustInfo(Vehicle &State) {
digitalWrite(pin_igniter, HIGH);
// Wait for motor to start burning
Serial.println("waiting for motor to start.");
while (lc_val * 1.5 < State.lc0_processed + State.lc1_processed +
State.lc2_processed + State.lc3_processed) {
;
Serial.println("Waiting for motor to start.");
while ((lc_val * 10) > (State.lc0_processed + State.lc1_processed +
State.lc2_processed + State.lc3_processed)) {
// Serial.print(lc_val * 10);
// Serial.print(", ");
// Serial.println(State.lc0_processed + State.lc1_processed +
// State.lc2_processed + State.lc3_processed);
}
State.thrustFiring = 1;
@ -269,6 +272,14 @@ void thrustInfo(Vehicle &State) {
} else {
State.thrust = 0.0;
State.Fx = 0.0;
State.Fy = 0.0;
State.Fz = g * State.massInitial;
State.momentX = 0.0;
State.momentY = 0.0;
State.momentZ = 0.0;
}
}

View File

@ -62,6 +62,7 @@ void setup() {
void loop() {
last = micros();
Serial.println(State.vz);
vehicleDynamics(State, PrevState);
thrustInfo(State);
@ -88,8 +89,13 @@ void loop() {
teensyAbort();
}
State.stepDuration = micros() - last;
delayMicroseconds((1000.0 * State.stepSize) - State.stepDuration);
if (State.burnElapsed < 0.01) {
State.stepDuration = State.stepSize;
} else {
State.stepDuration = micros() - last;
delayMicroseconds((1000.0 * State.stepSize) - State.stepDuration);
}
}
#endif