mirror of
https://gitlab.com/lander-team/lander-cpp.git
synced 2025-06-16 15:17:23 +00:00
New load cell calibration and exit condition
This commit is contained in:
parent
54a0beae49
commit
f9e7f8f283
@ -35,10 +35,10 @@ const int pin_lc2 = 19; // White
|
||||
const int pin_lc3 = 20; // Black
|
||||
const int pin_igniter = 7;
|
||||
|
||||
double lcGain0 = -98.32;
|
||||
double lcGain1 = -97.59;
|
||||
double lcGain2 = -100.51;
|
||||
double lcGain3 = -118.65;
|
||||
double lcGain0 = -107.39;
|
||||
double lcGain1 = -107.39;
|
||||
double lcGain2 = -107.39;
|
||||
double lcGain3 = -107.39;
|
||||
|
||||
// SD card stuff
|
||||
const int chipSelect = BUILTIN_SDCARD;
|
||||
@ -113,13 +113,13 @@ void initLoadCells(Vehicle &State) {
|
||||
lc2.set_scale();
|
||||
lc3.set_scale();
|
||||
|
||||
lc0.tare(50);
|
||||
lc0.tare(200);
|
||||
Serial.print(".");
|
||||
lc1.tare(50);
|
||||
lc1.tare(200);
|
||||
Serial.print(".");
|
||||
lc2.tare(50);
|
||||
lc2.tare(200);
|
||||
Serial.println(".");
|
||||
lc3.tare(50);
|
||||
lc3.tare(200);
|
||||
|
||||
// Attach ISRs to load cell data pins to read data when available
|
||||
attachInterrupt(digitalPinToInterrupt(pin_lc0), read_lc0, LOW);
|
||||
|
@ -75,7 +75,7 @@ void loop() {
|
||||
PrevState = State;
|
||||
State.time += State.stepSize;
|
||||
|
||||
if ((State.z < 0.0) && (State.thrustFiring == 2)) {
|
||||
if ((State.z < 0.0) ) {
|
||||
analogWrite(pin_igniter, 0);
|
||||
Serial.println("Run duration:" + String((micros() - initTime) / 1e6) +
|
||||
" seconds");
|
||||
|
Loading…
x
Reference in New Issue
Block a user