Skip to content

Commit 3b5d1e9

Browse files
committed
current sensing, to be tested
1 parent f5b2262 commit 3b5d1e9

File tree

1 file changed

+17
-2
lines changed

1 file changed

+17
-2
lines changed

Power Board/thrusters.ino

Lines changed: 17 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,7 @@ DO NOT FLASH TO TEENSY OR TO ARDUINO
3434
#define VBAT2_SENSE 23
3535

3636
// defines 8 thursters for initialization in an array
37+
// should be replaced with definitions from ROS
3738
#define SRG_P 0
3839
#define SRG_S 1
3940
#define SWY_BW 2
@@ -47,8 +48,11 @@ DO NOT FLASH TO TEENSY OR TO ARDUINO
4748
Servo thrusters[8];
4849

4950
// 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};
51+
uint16_t microseconds[] = {1500, 1500, 1500, 1500, 1500, 1500, 1500, 1500};
52+
const uint16_t offCommand[] = {1500, 1500, 1500, 1500, 1500, 1500, 1500, 1500};
53+
54+
// creates array for 8 thruster currents
55+
float currents[8];
5256

5357
// updates thrusters' pwm signals from array
5458
void updateThrusters(const uint16_t microseconds[8]) {
@@ -94,6 +98,17 @@ void waterInterrupt() {
9498
while (true) {}
9599
}
96100

101+
void senseCurrent(float currents[]) {
102+
currents[0] = ((analogRead(TC_1) * 3.3) / 1023) / 0.005;
103+
currents[1] = ((analogRead(TC_2) * 3.3) / 1023) / 0.005;
104+
currents[2] = ((analogRead(TC_3) * 3.3) / 1023) / 0.005;
105+
currents[3] = ((analogRead(TC_4) * 3.3) / 1023) / 0.005;
106+
currents[4] = ((analogRead(TC_5) * 3.3) / 1023) / 0.005;
107+
currents[5] = ((analogRead(TC_6) * 3.3) / 1023) / 0.005;
108+
currents[6] = ((analogRead(TC_7) * 3.3) / 1023) / 0.005;
109+
currents[7] = ((analogRead(TC_8) * 3.3) / 1023) / 0.005;
110+
}
111+
97112
void setup() {
98113
//pinMode(WATER_DETECTED, INPUT_PULLUP);
99114
//pinMode(MCU_KS, OUTPUT);

0 commit comments

Comments
 (0)