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

compiling 😆

This commit is contained in:
2021-11-12 13:35:06 -07:00
parent 01cf0966f2
commit 4ef7619217
3 changed files with 41 additions and 49 deletions

View File

@@ -10,8 +10,6 @@
#include <vector>
#elif defined(TEENSY)
#include <Arduino.h>
#include "HX711.h"
unsigned long last;
#endif
@@ -21,8 +19,18 @@ unsigned long last;
#if defined(NATIVE) || defined(_WIN32)
#include "native.h"
#elif defined(TEENSY)
#include "teensy.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
Vehicle State;
@@ -38,6 +46,17 @@ void setup() {
}
#elif defined(TEENSY)
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);
init_Vehicle(State);
Serial.println("Simulated Vehicle Initalized");
@@ -48,8 +67,6 @@ void setup() {
Serial.println("Starting Height Calculated");
delay(1000);
LoadCells loadCells;
init_LoadCells(loadCells);
Serial.println("Load Cells Calibrated");
@@ -81,7 +98,7 @@ void loop() {
thrustInfo(State);
pidController(State, PrevState);
TVC(State, PrevState);
processTVC(State);
processTVC(State, loadCells);
// state2vec(State, PrevState, stateVector);
State.time += State.stepSize;