Skip to content

Commit d3d9588

Browse files
committed
added thruster control code
1 parent c52090b commit d3d9588

File tree

2 files changed

+61
-0
lines changed

2 files changed

+61
-0
lines changed
Lines changed: 31 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,31 @@
1+
#include "ThrusterControl.h"
2+
3+
// Initialize thrusters
4+
Servo thrusters[8];
5+
6+
// Default microseconds for each thruster (centered at 1500)
7+
int16_t microseconds[8] = {1500, 1500, 1500, 1500, 1500, 1500, 1500, 1500};
8+
9+
// Off command to stop all thrusters (1500 microseconds)
10+
const int16_t offCommand[8] = {1500, 1500, 1500, 1500, 1500, 1500, 1500, 1500};
11+
12+
// Initializes all thrusters by attaching them to the correct pins
13+
void initThrusters() {
14+
thrusters[0].attach(THRUSTER_1);
15+
thrusters[1].attach(THRUSTER_2);
16+
thrusters[2].attach(THRUSTER_3);
17+
thrusters[3].attach(THRUSTER_4);
18+
thrusters[4].attach(THRUSTER_5);
19+
thrusters[5].attach(THRUSTER_6);
20+
thrusters[6].attach(THRUSTER_7);
21+
thrusters[7].attach(THRUSTER_8);
22+
23+
updateThrusters(offCommand); // Initialize all thrusters to the off state
24+
}
25+
26+
// Updates all thrusters' PWM signal based on the provided array
27+
void updateThrusters(const int16_t microseconds[8]) {
28+
for (int i = 0; i < 8; i++) {
29+
thrusters[i].writeMicroseconds(microseconds[i]);
30+
}
31+
}
Lines changed: 30 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,30 @@
1+
#ifndef THRUSTER_CONTROL_H
2+
#define THRUSTER_CONTROL_H
3+
4+
#include <Servo.h>
5+
6+
#define THRUSTER_1 2
7+
#define THRUSTER_2 3
8+
#define THRUSTER_3 4
9+
#define THRUSTER_4 5
10+
#define THRUSTER_5 6
11+
#define THRUSTER_6 7
12+
#define THRUSTER_7 8
13+
#define THRUSTER_8 9
14+
15+
// Create an array of 8 thrusters
16+
extern Servo thrusters[8];
17+
18+
// Define PWM signal (in microseconds) for each thruster
19+
extern int16_t microseconds[8];
20+
21+
// Define the off command for all thrusters
22+
extern const int16_t offCommand[8];
23+
24+
// Initializes the thrusters
25+
void initThrusters();
26+
27+
// Updates the thrusters' PWM signal
28+
void updateThrusters(int16_t microseconds[8]);
29+
30+
#endif

0 commit comments

Comments
 (0)