1
0
mirror of https://gitlab.com/lander-team/static-load-test-code.git synced 2025-06-15 14:46:47 +00:00

Implementing static load test

This commit is contained in:
Matthew Robinaugh 2021-11-17 15:38:51 -07:00
parent 4c038258f1
commit db4aee9d16
3 changed files with 167 additions and 1 deletions

3
include/LoadCells.h Normal file
View File

@ -0,0 +1,3 @@
struct LoadCells{
double lc0, lc1, lc2, lc3 = 0.0;
};

View File

@ -12,3 +12,4 @@
platform = teensy
board = teensy41
framework = arduino
lib_deps = bogde/HX711@^0.7.4

View File

@ -1,9 +1,171 @@
#include <Arduino.h>
#include "HX711.h"
#include "LoadCells.h"
#include "SD.h"
LoadCells State;
HX711 lc0;
HX711 lc1;
HX711 lc2;
HX711 lc3;
void write2CSV(struct LoadCells &);
void initFile();
void read_lc0();
void read_lc1();
void read_lc2();
void read_lc3();
const int lc_clock = 23;
const int pin_lc0 = 14;
const int pin_lc1 = 15;
const int pin_lc2 = 19;
const int pin_lc3 = 20;
double lc0Offset = 0.0;
double lc1Offset = 0.0;
double lc2Offset = 0.0;
double lc3Offset = 0.0;
const int chipSelect = BUILTIN_SDCARD;
File dataFile;
void setup() {
// put your setup code here, to run once:
pinMode(lc_clock, INPUT);
// Configure load cell data pins as inputs
pinMode(pin_lc0, INPUT);
pinMode(pin_lc1, INPUT);
pinMode(pin_lc2, INPUT);
pinMode(pin_lc3, INPUT);
lc0.begin(pin_lc0, lc_clock);
lc1.begin(pin_lc1, lc_clock);
lc2.begin(pin_lc2, lc_clock);
lc3.begin(pin_lc3, lc_clock);
lc0.set_scale();
lc1.set_scale();
lc2.set_scale();
lc3.set_scale();
lc0.tare(50);
lc1.tare(50);
lc2.tare(50);
lc3.tare(50);
// Attach ISRs to load cell data pins to read data when available
attachInterrupt(digitalPinToInterrupt(pin_lc0), read_lc0, LOW);
attachInterrupt(digitalPinToInterrupt(pin_lc1), read_lc1, LOW);
attachInterrupt(digitalPinToInterrupt(pin_lc2), read_lc2, LOW);
attachInterrupt(digitalPinToInterrupt(pin_lc3), read_lc3, LOW);
Serial.println("Load Cells Initialized");
Serial.println("Calibrating");
// Load Cell Tare
double lc0Tot = 0.0;
double lc1Tot = 0.0;
double lc2Tot = 0.0;
double lc3Tot = 0.0;
for (int i = 0; i < 50; i++) {
lc0Tot += State.lc0;
lc1Tot += State.lc1;
lc2Tot += State.lc2;
lc3Tot += State.lc3;
delay(50);
}
lc0Offset = lc0Tot / 50.0;
lc1Offset = lc1Tot / 50.0;
lc2Offset = lc2Tot / 50.0;
lc3Offset = lc3Tot / 50.0;
Serial.println(lc0Tot);
Serial.println(lc1Tot);
Serial.println(lc2Tot);
Serial.println(lc3Tot);
Serial.println("Load Cells Tared");
// Initializes State variables
State.lc0 = lc0.get_value();
State.lc1 = lc1.get_value();
State.lc2 = lc2.get_value();
State.lc3 = lc3.get_value();
}
void loop() {
// put your main code here, to run repeatedly:
}
write2CSV(State);
delay(20);
}
void read_lc0() { State.lc0 = lc0.get_value() - lc0Offset; }
void read_lc1() { State.lc1 = lc1.get_value() - lc1Offset; }
void read_lc2() { State.lc2 = lc2.get_value() - lc2Offset; }
void read_lc3() { State.lc3 = lc3.get_value() - lc3Offset; }
void write2CSV(LoadCells &State) {
dataFile.print(String(State.lc0, 5));
dataFile.print(",");
dataFile.print(String(State.lc1, 5));
dataFile.print(",");
dataFile.print(String(State.lc2, 5));
dataFile.print(",");
dataFile.print(String(State.lc3, 5));
dataFile.close();
}
void initFile(){
Serial.print("Initializing SD card...");
// see if the card is present and can be initialized:
if (!SD.begin(chipSelect)) {
Serial.println("Card failed, or not present. \n\nABORTING SIMULATION");
}
Serial.println("Card initialized.");
int i = 1;
const char *fileName;
if (SD.exists("simOut.csv")) {
while (i > 0.0) {
fileName = ("simOut_" + String(i) + ".csv").c_str();
if (!SD.exists(fileName)) {
// Open simOut_i.csv
dataFile = SD.open(fileName, FILE_WRITE);
if (dataFile) {
Serial.println("File successfully opened!");
} else {
// if the file didn't open, print an error:
Serial.println("Error opening output file. \n\nABORTING SIMULATION");
}
i = 0.0;
} else {
i++;
}
}
} else {
// Open simOut.csv
dataFile = SD.open("simOut.csv", FILE_WRITE);
if (dataFile) {
Serial.println("File successfully opened!");
} else {
// if the file didn't open, print an error:
Serial.println("Error opening output file. \n\nABORTING SIMULATION");
}
}
dataFile.println(
"lc0,lc1,lc2,lc3");
}