mirror of
https://gitlab.com/lander-team/lander-cpp.git
synced 2025-06-15 22:56:53 +00:00
Moved init_loadCells() to teensy.h
This commit is contained in:
parent
f7acf25479
commit
503bf40c5b
@ -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...");
|
||||
|
||||
|
53
src/main.cpp
53
src/main.cpp
@ -27,19 +27,6 @@ unsigned long last, initTime;
|
||||
#include <HX711.h>
|
||||
#include <PWMServo.h>
|
||||
|
||||
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;
|
||||
|
||||
void init_loadCells();
|
||||
void read_lc0();
|
||||
void read_lc1();
|
||||
void read_lc2();
|
||||
void read_lc3();
|
||||
|
||||
HX711 lc0;
|
||||
HX711 lc1;
|
||||
HX711 lc2;
|
||||
@ -63,7 +50,7 @@ void setup() {
|
||||
delay(1000);
|
||||
}
|
||||
|
||||
init_loadCells();
|
||||
init_loadCells(lc0, lc1, lc2, lc3);
|
||||
init_Vehicle(State);
|
||||
State.lc0 = lc0.get_value();
|
||||
State.lc1 = lc1.get_value();
|
||||
@ -119,46 +106,12 @@ void loop() {
|
||||
delay(State.stepSize - ((micros() - last) / 1000.0));
|
||||
}
|
||||
|
||||
void init_loadCells() {
|
||||
// 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");
|
||||
}
|
||||
|
||||
// ISRs to print data to serial monitor
|
||||
// ISRs to print data to serial monitor - These unfortunately can't move
|
||||
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(); }
|
||||
|
||||
#endif
|
||||
|
||||
#if defined(_WIN32) || defined(NATIVE)
|
||||
|
Loading…
x
Reference in New Issue
Block a user