1
0
mirror of https://gitlab.com/lander-team/lander-cpp.git synced 2025-07-23 14:41:25 +00:00

Moved init_loadCells() to teensy.h

This commit is contained in:
bpmcgeeney
2021-11-14 20:31:17 -07:00
parent f7acf25479
commit 503bf40c5b
2 changed files with 52 additions and 51 deletions

View File

@@ -1,11 +1,12 @@
#include "Vehicle.h"
#include <Arduino.h>
#include <HX711.h>
#include <PWMServo.h>
#include <SD.h>
#include <SPI.h>
void testGimbal(class PWMServo &, class PWMServo &);
double loadCellCalibrate();
void init_loadCells(class HX711 &, class HX711 &, class HX711 &, class HX711 &);
void initFile();
void thrustInfo(struct Vehicle &);
void processTVC(struct Vehicle &, class PWMServo &, class PWMServo &);
@@ -13,6 +14,18 @@ void write2CSV(struct Vehicle &);
void printSimResults(struct Vehicle &);
void teensyAbort();
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;
const int chipSelect = BUILTIN_SDCARD;
File dataFile;
@@ -63,6 +76,41 @@ void testGimbal(PWMServo &servo1, PWMServo &servo2) {
servo2.write(0);
}
void init_loadCells(HX711 &lc0, HX711 &lc1, HX711 &lc2, HX711 &lc3) {
// Configure clock pin with high impedance to protect
// pin (if this doesn't work, change to OUTPUT)
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);
// 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.print("Calibrating");
lc0.tare();
Serial.print(".");
lc1.tare();
Serial.print(".");
lc2.tare();
Serial.print(".");
lc3.tare();
Serial.println(".");
Serial.println("Load Cells Calibrated");
}
void initFile() {
Serial.print("Initializing SD card...");