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:
parent
f9e7f8f283
commit
7993aa752d
@ -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);
|
||||
|
||||
|
@ -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");
|
||||
|
||||
@ -75,8 +75,8 @@ void loop() {
|
||||
PrevState = State;
|
||||
State.time += State.stepSize;
|
||||
|
||||
if ((State.z < 0.0) ) {
|
||||
analogWrite(pin_igniter, 0);
|
||||
if ((State.z < 0.0)) {
|
||||
digitalWrite(pin_igniter, LOW);
|
||||
Serial.println("Run duration:" + String((micros() - initTime) / 1e6) +
|
||||
" seconds");
|
||||
printSimResults(State);
|
||||
|
Loading…
x
Reference in New Issue
Block a user