|
| 1 | +#include <Servo.h> |
| 2 | + |
| 3 | +// boolean for interrupts |
| 4 | +volatile bool interruptFlag = false; |
| 5 | + |
| 6 | +// defines all MCU pins |
| 7 | +#define SYSTEM_KILLED 0 |
| 8 | +#define THURSTERS_KILLED 1 |
| 9 | + |
| 10 | +#define SRG_P_PIN 2 |
| 11 | +#define SRG_S_PIN 3 |
| 12 | +#define SWY_BW_PIN 4 |
| 13 | +#define SWY_ST_PIN 5 |
| 14 | +#define HVE_BW_P_PIN 6 |
| 15 | +#define HVE_BW_S_PIN 7 |
| 16 | +#define HVE_ST_S_PIN 8 |
| 17 | +#define HVE_ST_P_PIN 9 |
| 18 | + |
| 19 | +#define MCU_KS 10 |
| 20 | +#define WATER_DETECTED 12 |
| 21 | + |
| 22 | +#define TEENSY_LED 13 |
| 23 | + |
| 24 | +#define TC_1 14 |
| 25 | +#define TC_2 15 |
| 26 | +#define TC_3 16 |
| 27 | +#define TC_4 17 |
| 28 | +#define TC_5 18 |
| 29 | +#define TC_6 19 |
| 30 | +#define TC_7 20 |
| 31 | +#define TC_8 21 |
| 32 | + |
| 33 | +#define VBAT1_SENSE 22 |
| 34 | +#define VBAT2_SENSE 23 |
| 35 | + |
| 36 | +// defines 8 thursters for initialization in an array |
| 37 | +#define SRG_P 0 |
| 38 | +#define SRG_S 1 |
| 39 | +#define SWY_BW 2 |
| 40 | +#define SWY_ST 3 |
| 41 | +#define HVE_BW_P 4 |
| 42 | +#define HVE_BW_S 5 |
| 43 | +#define HVE_ST_S 6 |
| 44 | +#define HVE_ST_P 7 |
| 45 | + |
| 46 | +// creates array of 8 thrusters |
| 47 | +Servo thrusters[8]; |
| 48 | + |
| 49 | +// signals to push to thrusters |
| 50 | +uint16_t microseconds[] = {1500, 1500, 1500, 1500, 1500, 1500, 1500, 1500}; |
| 51 | +const uint16_t offCommand[] = {1500, 1500, 1500, 1500, 1500, 1500, 1500, 1500}; |
| 52 | + |
| 53 | +// updates thrusters' pwm signals from array |
| 54 | +void updateThrusters(const uint16_t microseconds[8]) { |
| 55 | + thrusters[SRG_P].writeMicroseconds(microseconds[SRG_P]); |
| 56 | + thrusters[SRG_S].writeMicroseconds(microseconds[SRG_S]); |
| 57 | + thrusters[SWY_BW].writeMicroseconds(microseconds[SWY_BW]); |
| 58 | + thrusters[SWY_ST].writeMicroseconds(microseconds[SWY_ST]); |
| 59 | + thrusters[HVE_BW_P].writeMicroseconds(microseconds[HVE_BW_P]); |
| 60 | + thrusters[HVE_BW_S].writeMicroseconds(microseconds[HVE_BW_S]); |
| 61 | + thrusters[HVE_ST_P].writeMicroseconds(microseconds[HVE_ST_P]); |
| 62 | + thrusters[HVE_ST_S].writeMicroseconds(microseconds[HVE_ST_S]); |
| 63 | +} |
| 64 | + |
| 65 | +// attaches and arms thrusters |
| 66 | +void initThrusters() { |
| 67 | + interrupts(); |
| 68 | + interruptFlag = false; |
| 69 | + |
| 70 | + thrusters[SRG_P].attach(SRG_P_PIN); |
| 71 | + thrusters[SRG_S].attach(SRG_S_PIN); |
| 72 | + thrusters[SWY_BW].attach(SWY_BW_PIN); |
| 73 | + thrusters[SWY_ST].attach(SWY_ST_PIN); |
| 74 | + thrusters[HVE_BW_P].attach(HVE_BW_P_PIN); |
| 75 | + thrusters[HVE_BW_S].attach(HVE_BW_S_PIN); |
| 76 | + thrusters[HVE_ST_S].attach(HVE_ST_S_PIN); |
| 77 | + thrusters[HVE_ST_P].attach(HVE_ST_P_PIN); |
| 78 | + |
| 79 | + updateThrusters(offCommand); |
| 80 | + delay(7000); |
| 81 | +} |
| 82 | + |
| 83 | +void killSystem() { |
| 84 | + digitalWrite(MCU_KS, HIGH); |
| 85 | + delay(100); |
| 86 | +} |
| 87 | + |
| 88 | +void powerSystem() { |
| 89 | + digitalWrite(MCU_KS, LOW); |
| 90 | + delay(100); |
| 91 | +} |
| 92 | + |
| 93 | +void setup() { |
| 94 | + pinMode(SYSTEM_KILLED, INPUT_PULLUP); |
| 95 | + pinMode(THURSTERS_KILLED, INPUT_PULLUP); |
| 96 | + pinMode(WATER_DETECTED, INPUT_PULLUP); |
| 97 | + |
| 98 | + pinMode(MCU_KS, OUTPUT); |
| 99 | + |
| 100 | + attachInterrupt(digitalPinToInterrupt(SYSTEM_KILLED), initThrusters, RISING); |
| 101 | + attachInterrupt(digitalPinToInterrupt(THURSTERS_KILLED), initThrusters, RISING); |
| 102 | + attachInterrupt(digitalPinToInterrupt(WATER_DETECTED), killSystem, RISING); |
| 103 | + attachInterrupt(digitalPinToInterrupt(WATER_DETECTED), powerSystem, FALLING); |
| 104 | + |
| 105 | + initThrusters(); |
| 106 | +} |
| 107 | + |
| 108 | +void loop() { |
| 109 | + if (interruptFlag) { |
| 110 | + interruptFlag = false; |
| 111 | + } |
| 112 | + |
| 113 | + updateThrusters(microseconds); |
| 114 | +} |
0 commit comments