Skip to content

Commit cc26bf7

Browse files
authored
Merge pull request #126 from mcgill-robotics/jptesting
Test data performed in 2023-2024
2 parents c83706b + d37aec9 commit cc26bf7

File tree

7 files changed

+4896
-0
lines changed

7 files changed

+4896
-0
lines changed
Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,8 @@
1+
microseconds,mA,notes
2+
n/a,0.15,when thrusters are not connected
3+
1540,0.45,
4+
1600,1.6,
5+
1650,2.6,
6+
1700,3.7,
7+
1750,6.9,
8+
1775,9,approximate value
Lines changed: 148 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,148 @@
1+
/*
2+
3+
DO NOT FLASH TO TEENSY OR TO ARDUINO
4+
5+
*/
6+
7+
#include <Arduino.h>
8+
#include <Servo.h>
9+
10+
// defines all MCU pins
11+
#define SRG_P_PIN 2
12+
#define SRG_S_PIN 3
13+
#define SWY_BW_PIN 4
14+
#define SWY_ST_PIN 5
15+
#define HVE_BW_P_PIN 6
16+
#define HVE_BW_S_PIN 7
17+
#define HVE_ST_S_PIN 8
18+
#define HVE_ST_P_PIN 9
19+
20+
#define MCU_KS 10
21+
#define WATER_DETECTED 12
22+
23+
#define TEENSY_LED 13
24+
25+
#define TC_1 14
26+
#define TC_2 15
27+
#define TC_3 16
28+
#define TC_4 17
29+
#define TC_5 18
30+
#define TC_6 19
31+
#define TC_7 20
32+
#define TC_8 21
33+
34+
#define VBAT1_SENSE 22
35+
#define VBAT2_SENSE 23
36+
37+
// defines 8 thursters for initialization in an array
38+
// should be replaced with definitions from ROS
39+
#define SRG_P 0
40+
#define SRG_S 1
41+
#define SWY_BW 2
42+
#define SWY_ST 3
43+
#define HVE_BW_P 4
44+
#define HVE_BW_S 5
45+
#define HVE_ST_S 6
46+
#define HVE_ST_P 7
47+
48+
// creates array of 8 thrusters
49+
Servo thrusters[8];
50+
51+
// signals to push to thrusters
52+
uint16_t microseconds[] = {1500, 1500, 1500, 1500, 1500, 1500, 1500, 1500};
53+
const uint16_t offCommand[] = {1500, 1500, 1500, 1500, 1500, 1500, 1500, 1500};
54+
55+
// creates array for 8 thruster current sensing
56+
float Tcurrents[8];
57+
58+
// creates array for 2 battery voltage sensing
59+
float Bvoltages[2];
60+
61+
// updates thrusters' pwm signals from array
62+
void updateThrusters(const uint16_t microseconds[8]) {
63+
thrusters[SRG_P].writeMicroseconds(microseconds[SRG_P]);
64+
thrusters[SRG_S].writeMicroseconds(microseconds[SRG_S]);
65+
thrusters[SWY_BW].writeMicroseconds(microseconds[SWY_BW]);
66+
thrusters[SWY_ST].writeMicroseconds(microseconds[SWY_ST]);
67+
thrusters[HVE_BW_P].writeMicroseconds(microseconds[HVE_BW_P]);
68+
thrusters[HVE_BW_S].writeMicroseconds(microseconds[HVE_BW_S]);
69+
thrusters[HVE_ST_P].writeMicroseconds(microseconds[HVE_ST_P]);
70+
thrusters[HVE_ST_S].writeMicroseconds(microseconds[HVE_ST_S]);
71+
}
72+
73+
// attaches and arms thrusters
74+
void initThrusters() {
75+
thrusters[SRG_P].attach(SRG_P_PIN);
76+
thrusters[SRG_S].attach(SRG_S_PIN);
77+
thrusters[SWY_BW].attach(SWY_BW_PIN);
78+
thrusters[SWY_ST].attach(SWY_ST_PIN);
79+
thrusters[HVE_BW_P].attach(HVE_BW_P_PIN);
80+
thrusters[HVE_BW_S].attach(HVE_BW_S_PIN);
81+
thrusters[HVE_ST_S].attach(HVE_ST_S_PIN);
82+
thrusters[HVE_ST_P].attach(HVE_ST_P_PIN);
83+
84+
updateThrusters(offCommand);
85+
delay(7000);
86+
// reamring works when system killed automatically at 2000
87+
// 7000 should be tested since it is more reliable based on bluerobotics
88+
}
89+
90+
void killSystem() {
91+
digitalWrite(MCU_KS, HIGH);
92+
delay(100);
93+
}
94+
95+
void powerSystem() {
96+
digitalWrite(MCU_KS, LOW);
97+
delay(100);
98+
}
99+
100+
void waterInterrupt() {
101+
killSystem();
102+
while (true) {
103+
digitalWrite(TEENSY_LED, HIGH);
104+
delay(500);
105+
digitalWrite(TEENSY_LED, LOW);
106+
delay(500);
107+
}
108+
}
109+
110+
void senseCurrent(float Tcurrents[]) {
111+
Tcurrents[0] = (analogRead(TC_1)) / (0.005 * 50);
112+
Tcurrents[1] = (analogRead(TC_2)) / (0.005 * 50);
113+
Tcurrents[2] = (analogRead(TC_3)) / (0.005 * 50);
114+
Tcurrents[3] = (analogRead(TC_4)) / (0.005 * 50);
115+
Tcurrents[4] = (analogRead(TC_5)) / (0.005 * 50);
116+
Tcurrents[5] = (analogRead(TC_6)) / (0.005 * 50);
117+
Tcurrents[6] = (analogRead(TC_7)) / (0.005 * 50);
118+
Tcurrents[7] = (analogRead(TC_8)) / (0.005 * 50);
119+
}
120+
121+
void senseVoltage(float Bvoltages[]) {
122+
Bvoltages[0] = map(analogRead(VBAT1_SENSE), 0.180, 2.586, 12.8, 16.8);
123+
Bvoltages[1] = map(analogRead(VBAT2_SENSE), 0.180, 2.586, 12.8, 16.8);
124+
}
125+
126+
void setup() {
127+
//pinMode(WATER_DETECTED, INPUT_PULLUP);
128+
//pinMode(MCU_KS, OUTPUT);
129+
pinMode(TC_1, INPUT);
130+
pinMode(TC_2, INPUT);
131+
pinMode(TC_3, INPUT);
132+
pinMode(TC_4, INPUT);
133+
pinMode(TC_5, INPUT);
134+
pinMode(TC_6, INPUT);
135+
pinMode(TC_7, INPUT);
136+
pinMode(TC_8, INPUT);
137+
pinMode(VBAT1_SENSE, INPUT);
138+
pinMode(VBAT2_SENSE, INPUT);
139+
pinMode(TEENSY_LED, OUTPUT);
140+
141+
//attachInterrupt(digitalPinToInterrupt(WATER_DETECTED), waterInterrupt, RISING);
142+
143+
initThrusters();
144+
}
145+
146+
void loop() {
147+
updateThrusters(microseconds);
148+
}

0 commit comments

Comments
 (0)