Skip to content

Commit 7d7da7c

Browse files
committed
added website integration
1 parent a442b68 commit 7d7da7c

File tree

1,432 files changed

+367
-323
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

1,432 files changed

+367
-323
lines changed
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,275 @@
1+
2+
3+
#define joyX A0
4+
#define joyY A1
5+
#define SW 8
6+
//#include "EdgeImpulse_FOMO_NO_PSRAM.j"
7+
#include "Battlebots_inferencing.h"
8+
#include <eloquent_esp32cam.h>
9+
#include <eloquent_esp32cam/edgeimpulse/fomo.h>
10+
#include <WiFi.h>
11+
#include <WebServer.h>
12+
#include <ESP32Servo.h>
13+
#include "html_page.h"
14+
#include <tuple>
15+
// WiFi credentials
16+
const char* ssid = "henesp";
17+
const char* password = "12345678";
18+
19+
WebServer server(80);
20+
Servo ESC; // ESC control instance
21+
22+
// Motor pin definitions
23+
24+
using eloq::camera;
25+
using eloq::ei::fomo;
26+
27+
const int enA = 18;
28+
const int enB = 19;
29+
const int motor1_in1 = 3; // Motor 1 forward
30+
const int motor1_in2 = 4; // Motor 1 reverse
31+
const int motor2_in1 = 5; // Motor 2 forward
32+
const int motor2_in2 = 6; // Motor 2 reverse
33+
int motorSpeed1, motorSpeed2;
34+
const int IN1 = 12; // Motor 1 direction pin
35+
const int IN2 = 15; // Motor 1 direction pin
36+
const int ENA = 13; // Motor 1 speed
37+
38+
const int IN12 = 27; // Motor 2 direction pin
39+
const int IN22 = 26; // Motor 2 direction pin
40+
const int ENA2 = 25; // Motor 2 speed
41+
//in1 -> in2
42+
// in3 -> in4
43+
//FEEL FREE TO CHANGE PIN VALUES IN ORDER TO MATCH OUR CONFIGURATION WITH CIRCUIT BOARD
44+
//https://lastminuteengineers.com/l293d-dc-motor-arduino-tutorial/
45+
46+
47+
// Joystick values from HTML page
48+
int xValue = 50;
49+
int yValue = 50;
50+
int sliderValue = 0; // Used for controlling the ESC
51+
bool joystickEnabled = true;
52+
53+
void escControl() {
54+
int pwmVal = map(sliderValue, 0, 100, 0, 60); // Map slider (0-100) to ESC range (0-60)
55+
56+
// Dead zone to prevent unintended small values affecting ESC
57+
if (pwmVal > 0 && pwmVal < 10) {
58+
pwmVal = 0;
59+
}
60+
61+
ESC.write(pwmVal); // Write the PWM value to the ESC
62+
}
63+
void motorControl() {
64+
int motorSpeed = map(abs(yValue)-50, 50, 100, 0, 255); // Map yValue distance from 50 to motor speed
65+
66+
if (yValue > 50) { // Move forward
67+
digitalWrite(IN1, HIGH);
68+
digitalWrite(IN2, LOW);
69+
digitalWrite(IN12, HIGH);
70+
digitalWrite(IN22, LOW);
71+
} else if (yValue < 50) { // Move backward
72+
digitalWrite(IN1, LOW);
73+
digitalWrite(IN2, HIGH);
74+
digitalWrite(IN12, LOW);
75+
digitalWrite(IN22, HIGH);
76+
} else { // Stop
77+
motorSpeed = 0;
78+
}
79+
analogWrite(ENA, motorSpeed); // Set speed based on mapped value
80+
}
81+
82+
void handleRoot() {
83+
server.send(200, "text/html", htmlPage);
84+
}
85+
86+
std::tuple<int, int> detectX() {
87+
// Code to run the detection (similar to your original code)
88+
if (!camera.capture().isOk()) {
89+
Serial.println(camera.exception.toString());
90+
return std::make_tuple(0, 0);
91+
}
92+
93+
// run FOMO
94+
if (!fomo.run().isOk()) {
95+
Serial.println(fomo.exception.toString());
96+
return std::make_tuple(0, 0);
97+
}
98+
99+
// how many objects were found?
100+
Serial.printf(
101+
"Found %d object(s) in %dms\n",
102+
fomo.count(),
103+
fomo.benchmark.millis());
104+
105+
// if no object is detected, return
106+
if (!fomo.foundAnyObject())
107+
return std::make_tuple(0, 0);
108+
109+
// if you expect to find a single object, use fomo.first
110+
111+
112+
int x = (int)fomo.first.x;
113+
int probability = (int)fomo.first.proba;
114+
return std::make_tuple(x, probability);
115+
}
116+
void handleUpdate() {
117+
if (server.hasArg("x") && server.hasArg("y") && server.hasArg("s")) {
118+
xValue = server.arg("x").toInt();
119+
yValue = server.arg("y").toInt();
120+
sliderValue = server.arg("s").toInt();
121+
122+
Serial.printf("X: %d, Y: %d, Slider: %d\n", xValue, yValue, sliderValue);
123+
server.send(200, "text/plain", "OK");
124+
} else {
125+
server.send(400, "text/plain", "Bad Request");
126+
}
127+
}
128+
129+
130+
void control(int xValue, int yValue) {
131+
132+
133+
// Map joystick values to motor speeds (-255 to 255 for PWM control)
134+
int speed = map(yValue, 0, 1023, -255, 255); // Forward/backward control
135+
int turn = map(xValue, 0, 1023, -255, 255); // Left/right control
136+
137+
// Calculate individual motor speeds for differential drive
138+
motorSpeed1 = speed + turn; // Left motor speed
139+
140+
motorSpeed2 = speed - turn; // Right motor speed
141+
142+
// Limit motor speed to max PWM values (-255 to 255)
143+
motorSpeed1 = constrain(motorSpeed1, -255, 255);
144+
motorSpeed2 = constrain(motorSpeed2, -255, 255);
145+
146+
// Control left motor
147+
if (motorSpeed1 > 0) {
148+
digitalWrite(motor1_in1, HIGH);
149+
digitalWrite(motor1_in2, LOW);
150+
} else if (motorSpeed1 < 0) {
151+
digitalWrite(motor1_in1, LOW);
152+
digitalWrite(motor1_in2, HIGH);
153+
} else {
154+
digitalWrite(motor1_in1, LOW);
155+
digitalWrite(motor1_in2, LOW);
156+
}
157+
158+
// Control right motor
159+
if (motorSpeed2 > 0) {
160+
digitalWrite(motor2_in1, HIGH);
161+
digitalWrite(motor2_in2, LOW);
162+
} else if (motorSpeed2 < 0) {
163+
digitalWrite(motor2_in1, LOW);
164+
digitalWrite(motor2_in2, HIGH);
165+
} else {
166+
digitalWrite(motor2_in1, LOW);
167+
digitalWrite(motor2_in2, LOW);
168+
}
169+
170+
// Set motor speeds using PWM
171+
analogWrite(enA, abs(motorSpeed1));
172+
analogWrite(enB, abs(motorSpeed2));
173+
174+
// Optional: Stop motors if the joystick button is pressed
175+
//if (digitalRead(SW) == LOW) {
176+
// stopMotors();
177+
//}
178+
179+
delay(10); // Short delay to allow stable readings
180+
}
181+
182+
183+
void AIcontrol() {
184+
//Fill this in later based on x bounds for the camera...
185+
int xMin = 0, xMax = 96;
186+
int xValue, prob;
187+
std::tie(xValue, prob) = detectX();
188+
if (prob > 20) //if probable detection
189+
{
190+
int yValue = 1023;
191+
xValue = map(xValue, xMin, xMax, -255, 255);
192+
control(xValue, yValue);
193+
} else //if not probable, rotate in a fixed circle
194+
{
195+
idle();
196+
}
197+
}
198+
199+
void idle() {
200+
digitalWrite(motor1_in1, HIGH);
201+
digitalWrite(motor1_in2, LOW);
202+
digitalWrite(motor2_in2, HIGH);
203+
digitalWrite(motor2_in1, LOW);
204+
analogWrite(enA, 255);
205+
analogWrite(enB, 255);
206+
}
207+
208+
209+
210+
211+
void stopMotors() {
212+
digitalWrite(motor1_in1, LOW);
213+
digitalWrite(motor1_in2, LOW);
214+
digitalWrite(motor2_in1, LOW);
215+
digitalWrite(motor2_in2, LOW);
216+
}
217+
218+
void setup() {
219+
delay(3000);
220+
Serial.begin(115200);
221+
Serial.println("__EDGE IMPULSE FOMO (NO-PSRAM)__");
222+
Serial.begin(115200);
223+
224+
// Setup WiFi
225+
WiFi.softAP(ssid, password);
226+
Serial.println("Access point started");
227+
Serial.printf("IP Address: %s\n", WiFi.softAPIP().toString().c_str());
228+
229+
// Setup server routes
230+
server.on("/", handleRoot);
231+
server.on("/u", handleUpdate);
232+
server.begin();
233+
Serial.println("Server started");
234+
235+
// Initialize ESC
236+
ESC.attach(32); // Connect ESC to pin 13
237+
ESC.write(0); // Stop ESC initially
238+
delay(1000); // Allow time for ESC initialization
239+
240+
// Initialize motor pins
241+
pinMode(IN1, OUTPUT);
242+
pinMode(IN2, OUTPUT);
243+
pinMode(ENA, OUTPUT);
244+
// camera settings
245+
// replace with your own model!
246+
// Configure the camera pins for Freenove ESP32-S3 WROOM
247+
camera.pinout.freenove_s3();
248+
249+
250+
251+
camera.brownout.disable();
252+
// NON-PSRAM FOMO only works on 96x96 (yolo) RGB565 images
253+
camera.resolution.yolo();
254+
camera.pixformat.rgb565();
255+
delay(3000);
256+
// init camera
257+
while (!camera.begin().isOk()) {
258+
Serial.println(camera.exception.toString());
259+
delay(3000);
260+
}
261+
262+
263+
Serial.println("Camera OK");
264+
Serial.println("Put object in front of camera");
265+
}
266+
void loop() {
267+
// Read joystick values
268+
if (!joyStickEnabled) {
269+
AIcontrol();
270+
} else {
271+
escControl(); // Control ESC based on slider input
272+
motorControl(); // Control motors based on joystick yValue
273+
server.handleClient(); // Handle web server requests
274+
}
275+
}
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,86 @@
1+
#include <BattleBotDetection.h>
2+
#include <tuple>
3+
BattleBotDetection::BattleBotDetection() {//constructor
4+
}
5+
6+
void BattleBotDetection::begin() {
7+
delay(3000);
8+
Serial.begin(115200);
9+
Serial.println("__EDGE IMPULSE FOMO (NO-PSRAM)__");
10+
11+
// Configure the camera pins for Freenove ESP32-S3 WROOM
12+
camera.pinout.freenove_s3();
13+
14+
15+
16+
camera.brownout.disable();
17+
// NON-PSRAM FOMO only works on 96x96 (yolo) RGB565 images
18+
camera.resolution.yolo();
19+
camera.pixformat.rgb565();
20+
delay(3000);
21+
// init camera
22+
while (!camera.begin().isOk())
23+
{
24+
Serial.println(camera.exception.toString());
25+
delay(3000);
26+
}
27+
}
28+
29+
std::tuple<int, int> BattleBotDetection::detectX() {
30+
// Code to run the detection (similar to your original code)
31+
if (!camera.capture().isOk()) {
32+
Serial.println(camera.exception.toString());
33+
return make_tuple(0,0);
34+
}
35+
36+
// run FOMO
37+
if (!fomo.run().isOk()) {
38+
Serial.println(fomo.exception.toString());
39+
return make_tuple(0,0);
40+
}
41+
42+
// how many objects were found?
43+
Serial.printf(
44+
"Found %d object(s) in %dms\n",
45+
fomo.count(),
46+
fomo.benchmark.millis()
47+
);
48+
49+
// if no object is detected, return
50+
if (!fomo.foundAnyObject())
51+
return make_tuple(0,0);
52+
53+
// if you expect to find a single object, use fomo.first
54+
/*
55+
Serial.printf(
56+
"Found %s at (x = %d, y = %d) (size %d x %d). "
57+
"Proba is %.2f\n",
58+
fomo.first.label,
59+
fomo.first.x,
60+
fomo.first.y,
61+
fomo.first.width,
62+
fomo.first.height,
63+
fomo.first.proba
64+
);
65+
*/
66+
int x = int(fomo.first.x())
67+
int probability = (int)fomo.first.proba()
68+
return make_tuple( x,probability );
69+
}
70+
71+
void BattleBotDetection::printResults() {
72+
// Print detection results to the serial monitor
73+
fomo.forEach([](int i, bbox_t bbox) {
74+
Serial.printf(
75+
"#%d) Found %s at (x = %d, y = %d) (size %d x %d). "
76+
"Proba is %.2f\n",
77+
i + 1,
78+
bbox.label,
79+
bbox.x,
80+
bbox.y,
81+
bbox.width,
82+
bbox.height,
83+
bbox.proba
84+
);
85+
});
86+
}

0 commit comments

Comments
 (0)