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

New tare size and digitalWrite for igniter

This commit is contained in:
bpmcgeeney 2021-11-24 11:16:44 -07:00
parent f9e7f8f283
commit 7993aa752d
2 changed files with 8 additions and 8 deletions

View File

@ -113,13 +113,13 @@ void initLoadCells(Vehicle &State) {
lc2.set_scale();
lc3.set_scale();
lc0.tare(200);
lc0.tare(50);
Serial.print(".");
lc1.tare(200);
lc1.tare(50);
Serial.print(".");
lc2.tare(200);
lc2.tare(50);
Serial.println(".");
lc3.tare(200);
lc3.tare(50);
// Attach ISRs to load cell data pins to read data when available
attachInterrupt(digitalPinToInterrupt(pin_lc0), read_lc0, LOW);
@ -204,7 +204,7 @@ void thrustInfo(Vehicle &State) {
State.burnStart = State.time;
State.burnElapsed = 0.0;
analogWrite(pin_igniter, 256);
digitalWrite(pin_igniter, HIGH);
State.thrustFiring = 1;
// getThrust(State);

View File

@ -51,7 +51,7 @@ void setup() {
Serial.println("Simulated Vehicle Initalized");
// Determine when to burn
analogWrite(pin_igniter, 0);
digitalWrite(pin_igniter, LOW);
burnStartTimeCalc(State);
Serial.println("Starting Height Calculated");
@ -76,7 +76,7 @@ void loop() {
State.time += State.stepSize;
if ((State.z < 0.0)) {
analogWrite(pin_igniter, 0);
digitalWrite(pin_igniter, LOW);
Serial.println("Run duration:" + String((micros() - initTime) / 1e6) +
" seconds");
printSimResults(State);