1
0
mirror of https://gitlab.com/lander-team/lander-cpp.git synced 2025-08-02 11:31:34 +00:00

load cell integration

This commit is contained in:
2021-11-13 14:48:12 -07:00
parent c05bbb6845
commit 812f62f22a
4 changed files with 67 additions and 68 deletions

View File

@@ -23,10 +23,8 @@ unsigned long last, initTime;
outVector stateVector;
#elif defined(TEENSY)
#include "LoadCells.h"
LoadCells loadCells;
#include "teensy.h"
#include <HX711.h>
const int lc_clock = 23;
const int lc_data_0 = 14;
@@ -34,6 +32,16 @@ const int lc_data_1 = 15;
const int lc_data_2 = 19;
const int lc_data_3 = 20;
void read_lc0();
void read_lc1();
void read_lc2();
void read_lc3();
HX711 lc0;
HX711 lc1;
HX711 lc2;
HX711 lc3;
#endif
Vehicle State;
@@ -58,20 +66,37 @@ void setup() {
pinMode(lc_data_1, INPUT);
pinMode(lc_data_2, INPUT);
pinMode(lc_data_3, INPUT);
loadCells.lc0.begin(lc_data_0, lc_clock);
loadCells.lc1.begin(lc_data_1, lc_clock);
loadCells.lc2.begin(lc_data_2, lc_clock);
loadCells.lc3.begin(lc_data_3, lc_clock);
lc0.begin(lc_data_0, lc_clock);
lc1.begin(lc_data_1, lc_clock);
lc2.begin(lc_data_2, lc_clock);
lc3.begin(lc_data_3, lc_clock);
// Attach ISRs to load cell data pins to read data when available
attachInterrupt(digitalPinToInterrupt(lc_data_0), read_lc0, LOW);
attachInterrupt(digitalPinToInterrupt(lc_data_1), read_lc1, LOW);
attachInterrupt(digitalPinToInterrupt(lc_data_2), read_lc2, LOW);
attachInterrupt(digitalPinToInterrupt(lc_data_3), read_lc3, LOW);
Serial.println("Load Cells Initialized");
loadCells.lc0Cal = loadCellCalibrate(loadCells.lc0);
loadCells.lc1Cal = loadCellCalibrate(loadCells.lc1);
loadCells.lc2Cal = loadCellCalibrate(loadCells.lc2);
loadCells.lc3Cal = loadCellCalibrate(loadCells.lc3);
Serial.print("Calibrating");
lc0.tare();
Serial.print(".");
lc1.tare();
Serial.print(".");
lc2.tare();
Serial.print(".");
lc3.tare();
Serial.println(".");
Serial.println("Load Cells Calibrated");
delay(1000);
init_Vehicle(State);
State.lc0 = lc0.get_value();
State.lc1 = lc1.get_value();
State.lc2 = lc2.get_value();
State.lc3 = lc3.get_value();
Serial.println("Simulated Vehicle Initalized");
delay(1000);
@@ -80,8 +105,6 @@ void setup() {
Serial.println("Starting Height Calculated");
delay(1000);
Serial.println("Load Cells Calibrated");
delay(1000);
initFile();
delay(1000);
@@ -112,16 +135,17 @@ void loop() {
void loop() {
last = micros();
update_LoadCells(loadCells);
Serial.println(State.time);
vehicleDynamics(State, PrevState);
thrustInfo(State);
pidController(State, PrevState);
TVC(State, PrevState);
processTVC(State, loadCells);
processTVC(State);
delay(2);
State.stepDuration = micros() - last;
write2CSV(State, loadCells);
write2CSV(State);
// Set "prev" values for next timestep
PrevState = State;
@@ -156,4 +180,13 @@ int main() {
return 0;
}
#endif
#endif
// ISRs to print data to serial monitor
void read_lc0() { State.lc0 = lc0.get_value(); }
void read_lc1() { State.lc1 = lc1.get_value(); }
void read_lc2() { State.lc2 = lc2.get_value(); }
void read_lc3() { State.lc3 = lc3.get_value(); }