-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathController.ino
139 lines (117 loc) · 3.86 KB
/
Controller.ino
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
#include <Bluepad32.h>
int constr = 255;
class RhinoMotor {
public:
int _DIR_PIN;
int _PWM_PIN;
RhinoMotor(int DIR_PIN, int PWM_PIN) : _DIR_PIN(DIR_PIN), _PWM_PIN(PWM_PIN) {
pinMode(_DIR_PIN, OUTPUT);
pinMode(_PWM_PIN, OUTPUT);
}
void setSpeed(int speed) {
if (speed >= 0) {
// Forward
digitalWrite(_DIR_PIN, HIGH);
analogWrite(_PWM_PIN, speed);
} else {
// Backward
digitalWrite(_DIR_PIN, LOW);
analogWrite(_PWM_PIN, -speed);
}
}
void stop() {
analogWrite(_PWM_PIN, 0);
}
};
#define PWM_1 4
#define DIR_1 16
#define PWM_2 17
#define DIR_2 5
RhinoMotor Motor_1(DIR_1, PWM_1);
RhinoMotor Motor_2(DIR_2, PWM_2);
ControllerPtr myControllers[BP32_MAX_GAMEPADS];
void onConnectedController(ControllerPtr ctl) {
bool foundEmptySlot = false;
for (int i = 0; i < BP32_MAX_GAMEPADS; i++) {
if (myControllers[i] == nullptr) {
Serial.printf("CALLBACK: Controller is connected, index=%d\n", i);
ControllerProperties properties = ctl->getProperties();
Serial.printf("Controller model: %s, VID=0x%04x, PID=0x%04x\n", ctl->getModelName().c_str(), properties.vendor_id,
properties.product_id);
myControllers[i] = ctl;
foundEmptySlot = true;
break;
}
}
if (!foundEmptySlot) {
Serial.println("CALLBACK: Controller connected, but no empty slot found");
}
}
// Callback for when a controller is disconnected
void onDisconnectedController(ControllerPtr ctl) {
bool foundController = false;
for (int i = 0; i < BP32_MAX_GAMEPADS; i++) {
if (myControllers[i] == ctl) {
Serial.printf("CALLBACK: Controller disconnected from index=%d\n", i);
myControllers[i] = nullptr;
foundController = true;
break;
}
}
if (!foundController) {
Serial.println("CALLBACK: Controller disconnected, but not found in myControllers");
}
}
// Function to process gamepad inputs and control motors
void processGamepad(ControllerPtr ctl) {
if (ctl->a()) {
ctl->playDualRumble(0, 250, 0x80, 0x40);
Motor_1.stop();
Motor_2.stop();
return;
}
if (ctl->b()) {
constr = 200;
}
if (ctl->x()) {
constr = 255;
}
int left_axis = -ctl->axisY();
int right_axis = ctl->axisRX();
int left_axis_mapped = map(left_axis, -512, 512, -255, 255);
int right_axis_mapped = map(right_axis, -512, 512, -255, 255);
int motor_left_speed = left_axis_mapped - right_axis_mapped;
int motor_right_speed = left_axis_mapped + right_axis_mapped;
motor_left_speed = constrain(motor_left_speed, -constr, constr);
motor_right_speed = constrain(motor_right_speed, -constr, constr);
Motor_1.setSpeed(motor_left_speed);
Motor_2.setSpeed(motor_right_speed);
Serial.printf("%d %d\n", motor_left_speed, motor_right_speed);
}
void processControllers() {
for (auto myController : myControllers) {
if (myController && myController->isConnected() && myController->hasData()) {
if (myController->isGamepad()) {
processGamepad(myController);
} else {
Serial.println("Unsupported controller type");
}
}
}
}
void setup() {
Serial.begin(115200);
Serial.printf("Firmware: %s\n", BP32.firmwareVersion());
const uint8_t* addr = BP32.localBdAddress();
Serial.printf("BD Addr: %2X:%2X:%2X:%2X:%2X:%2X\n", addr[0], addr[1], addr[2], addr[3], addr[4], addr[5]);
BP32.setup(&onConnectedController, &onDisconnectedController);
BP32.forgetBluetoothKeys();
BP32.enableVirtualDevice(false);
}
void loop() {
bool dataUpdated = BP32.update();
if (dataUpdated) {
processControllers();
}
delay(150);
}