mirror of
https://gitlab.com/lander-team/lander-cpp.git
synced 2025-06-16 15:17:23 +00:00
compiling 😆
This commit is contained in:
parent
01cf0966f2
commit
4ef7619217
@ -1,3 +1,6 @@
|
|||||||
|
|
||||||
|
#include <HX711.h>
|
||||||
|
|
||||||
struct LoadCells {
|
struct LoadCells {
|
||||||
HX711 loadcell_0;
|
HX711 loadcell_0;
|
||||||
HX711 loadcell_1;
|
HX711 loadcell_1;
|
||||||
@ -15,35 +18,18 @@ struct LoadCells {
|
|||||||
double lc3Calibration;
|
double lc3Calibration;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
double loadCellCalibrate(HX711 loadCell) {
|
||||||
|
// place code to calibrate load cells in here
|
||||||
|
double loadTotal = 0.0;
|
||||||
|
for (int t = 0; t == 10; ++t) {
|
||||||
|
loadTotal += loadCell.read();
|
||||||
|
delay(15);
|
||||||
|
}
|
||||||
|
return loadTotal / 10.0;
|
||||||
|
}
|
||||||
|
|
||||||
void init_LoadCells(LoadCells &loadCells) {
|
void init_LoadCells(LoadCells &loadCells) {
|
||||||
|
|
||||||
loadCells.lc0Value = 0.0;
|
|
||||||
loadCells.lc1Value = 0.0;
|
|
||||||
loadCells.lc2Value = 0.0;
|
|
||||||
loadCells.lc3Value = 0.0;
|
|
||||||
|
|
||||||
const int lc_clock = 23;
|
|
||||||
|
|
||||||
const int lc_data_0 = 0;
|
|
||||||
const int lc_data_1 = 1;
|
|
||||||
const int lc_data_2 = 2;
|
|
||||||
const int lc_data_3 = 3;
|
|
||||||
|
|
||||||
Serial.begin(9600);
|
|
||||||
// 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(lc_data_0, INPUT);
|
|
||||||
pinMode(lc_data_1, INPUT);
|
|
||||||
pinMode(lc_data_2, INPUT);
|
|
||||||
pinMode(lc_data_3, INPUT);
|
|
||||||
|
|
||||||
loadCells.loadcell_0.begin(lc_data_0, lc_clock);
|
|
||||||
loadCells.loadcell_1.begin(lc_data_1, lc_clock);
|
|
||||||
loadCells.loadcell_2.begin(lc_data_2, lc_clock);
|
|
||||||
loadCells.loadcell_3.begin(lc_data_3, lc_clock);
|
|
||||||
|
|
||||||
loadCells.lc0Calibration = loadCellCalibrate(loadCells.loadcell_0);
|
loadCells.lc0Calibration = loadCellCalibrate(loadCells.loadcell_0);
|
||||||
loadCells.lc1Calibration = loadCellCalibrate(loadCells.loadcell_1);
|
loadCells.lc1Calibration = loadCellCalibrate(loadCells.loadcell_1);
|
||||||
loadCells.lc2Calibration = loadCellCalibrate(loadCells.loadcell_2);
|
loadCells.lc2Calibration = loadCellCalibrate(loadCells.loadcell_2);
|
||||||
|
@ -1,23 +1,10 @@
|
|||||||
#include "Vehicle.h"
|
#include "Vehicle.h"
|
||||||
#include "LoadCells.h"
|
|
||||||
|
|
||||||
void thrustInfo(struct Vehicle &);
|
void thrustInfo(struct Vehicle &);
|
||||||
void processTVC(struct LoadCells &);
|
void processTVC(struct LoadCells &);
|
||||||
void write2CSV(struct outVector &, struct Vehicle &);
|
void write2CSV(struct outVector &, struct Vehicle &);
|
||||||
void printSimResults(struct Vehicle &);
|
void printSimResults(struct Vehicle &);
|
||||||
|
|
||||||
double loadCellCalibrate(HX711 loadCell);
|
|
||||||
|
|
||||||
double loadCellCalibrate(HX711 loadCell) {
|
|
||||||
// place code to calibrate load cells in here
|
|
||||||
double loadTotal = 0.0;
|
|
||||||
for (double t = 0; t == 10; ++t) {
|
|
||||||
loadTotal += loadCell.read();
|
|
||||||
delay(15);
|
|
||||||
}
|
|
||||||
return loadTotal / 10.0;
|
|
||||||
}
|
|
||||||
|
|
||||||
void thrustInfo(Vehicle &State) {
|
void thrustInfo(Vehicle &State) {
|
||||||
if (State.time == 0) {
|
if (State.time == 0) {
|
||||||
Serial.println("WARNING: thrustInfo not implemented for TEENSY");
|
Serial.println("WARNING: thrustInfo not implemented for TEENSY");
|
||||||
@ -60,14 +47,16 @@ void thrustInfo(Vehicle &State) {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void processTVC(LoadCells &loadCells) {
|
void processTVC(Vehicle &State, LoadCells &loadCells) {
|
||||||
if (State.time == 0) {
|
if (State.time == 0) {
|
||||||
Serial.println("WARNING: processTVC not implemented for TEENSY");
|
Serial.println("WARNING: processTVC not implemented for TEENSY");
|
||||||
}
|
}
|
||||||
|
|
||||||
// Vector math to aqcuire thrust vector components
|
// Vector math to aqcuire thrust vector components
|
||||||
State.Fx = State.thrust * sin(State.xServoDegs * (M_PI / 180));
|
// PLACEHOLDER PLACEHOLDERPLACEHOLDER PLACEHOLDERPLACEHOLDER
|
||||||
State.Fy = State.thrust * sin(State.yServoDegs * (M_PI / 180));
|
// PLACEHOLDERPLACEHOLDER PLACEHOLDERPLACEHOLDER PLACEHOLDER
|
||||||
|
State.Fx = loadCells.lc1Value + loadCells.lc2Value;
|
||||||
|
State.Fy = loadCells.lc0Value + loadCells.lc3Value;
|
||||||
State.Fz = sqrt(pow(State.thrust, 2) - pow(State.Fx, 2) - pow(State.Fy, 2)) +
|
State.Fz = sqrt(pow(State.thrust, 2) - pow(State.Fx, 2) - pow(State.Fy, 2)) +
|
||||||
(State.mass * g);
|
(State.mass * g);
|
||||||
|
|
||||||
|
29
src/main.cpp
29
src/main.cpp
@ -10,8 +10,6 @@
|
|||||||
#include <vector>
|
#include <vector>
|
||||||
#elif defined(TEENSY)
|
#elif defined(TEENSY)
|
||||||
#include <Arduino.h>
|
#include <Arduino.h>
|
||||||
#include "HX711.h"
|
|
||||||
|
|
||||||
unsigned long last;
|
unsigned long last;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@ -21,8 +19,18 @@ unsigned long last;
|
|||||||
#if defined(NATIVE) || defined(_WIN32)
|
#if defined(NATIVE) || defined(_WIN32)
|
||||||
#include "native.h"
|
#include "native.h"
|
||||||
#elif defined(TEENSY)
|
#elif defined(TEENSY)
|
||||||
#include "teensy.h"
|
|
||||||
#include "LoadCells.h"
|
#include "LoadCells.h"
|
||||||
|
LoadCells loadCells;
|
||||||
|
|
||||||
|
#include "teensy.h"
|
||||||
|
const int lc_clock = 23;
|
||||||
|
|
||||||
|
const int lc_data_0 = 0;
|
||||||
|
const int lc_data_1 = 1;
|
||||||
|
const int lc_data_2 = 2;
|
||||||
|
const int lc_data_3 = 3;
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
Vehicle State;
|
Vehicle State;
|
||||||
@ -38,6 +46,17 @@ void setup() {
|
|||||||
}
|
}
|
||||||
#elif defined(TEENSY)
|
#elif defined(TEENSY)
|
||||||
void setup() {
|
void setup() {
|
||||||
|
Serial.begin(9600);
|
||||||
|
|
||||||
|
// 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(lc_data_0, INPUT);
|
||||||
|
pinMode(lc_data_1, INPUT);
|
||||||
|
pinMode(lc_data_2, INPUT);
|
||||||
|
pinMode(lc_data_3, INPUT);
|
||||||
|
|
||||||
delay(1000);
|
delay(1000);
|
||||||
init_Vehicle(State);
|
init_Vehicle(State);
|
||||||
Serial.println("Simulated Vehicle Initalized");
|
Serial.println("Simulated Vehicle Initalized");
|
||||||
@ -48,8 +67,6 @@ void setup() {
|
|||||||
Serial.println("Starting Height Calculated");
|
Serial.println("Starting Height Calculated");
|
||||||
delay(1000);
|
delay(1000);
|
||||||
|
|
||||||
LoadCells loadCells;
|
|
||||||
|
|
||||||
init_LoadCells(loadCells);
|
init_LoadCells(loadCells);
|
||||||
|
|
||||||
Serial.println("Load Cells Calibrated");
|
Serial.println("Load Cells Calibrated");
|
||||||
@ -81,7 +98,7 @@ void loop() {
|
|||||||
thrustInfo(State);
|
thrustInfo(State);
|
||||||
pidController(State, PrevState);
|
pidController(State, PrevState);
|
||||||
TVC(State, PrevState);
|
TVC(State, PrevState);
|
||||||
processTVC(State);
|
processTVC(State, loadCells);
|
||||||
// state2vec(State, PrevState, stateVector);
|
// state2vec(State, PrevState, stateVector);
|
||||||
|
|
||||||
State.time += State.stepSize;
|
State.time += State.stepSize;
|
||||||
|
Loading…
x
Reference in New Issue
Block a user