diff --git a/Odometry/code/code.ino b/Odometry/code/code.ino new file mode 100644 index 0000000..248c374 --- /dev/null +++ b/Odometry/code/code.ino @@ -0,0 +1,72 @@ +/* + * This example shows how to use WebSerial variant to send logging data to the browser. + * + * Before using this example, make sure to look at the WebSerial example before and its description.\ + * + * You might want to control these flags to control the async library performance: + * -D CONFIG_ASYNC_TCP_QUEUE_SIZE=64 + * -D CONFIG_ASYNC_TCP_RUNNING_CORE=1 + * -D WS_MAX_QUEUED_MESSAGES=128 + */ +#include +#if defined(ESP8266) +#include +#include +#elif defined(ESP32) +#include +#include +#endif +#include +#include +#include +#include + +AsyncWebServer server(80); +WebSerial webSerial; + +static uint32_t last = millis(); +static uint32_t count = 0; + +const char* ssid = "Dialog NNJ"; +const char* password = "Mixtures"; + +void setup() { + Serial.begin(115200); + + // Connect to WiFi in Station Mode + WiFi.mode(WIFI_STA); + WiFi.begin(ssid, password); + Serial.println("Connecting to WiFi..."); + + while (WiFi.status() != WL_CONNECTED) { + delay(500); + Serial.print("."); + } + Serial.println("") + + Serial.println("\nConnected! IP address: "); + Serial.println(WiFi.localIP()); + + webSerial.onMessage([](const std::string& msg) { Serial.println(msg.c_str()); }); + webSerial.begin(&server); + webSerial.setBuffer(100); + + server.onNotFound([](AsyncWebServerRequest* request) { request->redirect("/webserial"); }); + server.begin(); +//////////////////////////////////// + + +} + +void loop() { + if (millis() - last > 1000) { + count++; + + webSerial.print(F("IP address: ")); + webSerial.println(WiFi.softAPIP()); + webSerial.printf("Uptime: %lums\n", millis()); + webSerial.printf("Free heap: %" PRIu32 "\n", ESP.getFreeHeap()); + + last = millis(); + } +} diff --git a/Odometry/code/data/ESPAsyncWebServer.zip b/Odometry/code/data/ESPAsyncWebServer.zip new file mode 100644 index 0000000..a7b76d7 Binary files /dev/null and b/Odometry/code/data/ESPAsyncWebServer.zip differ diff --git a/Odometry/code/motor_control.h b/Odometry/code/motor_control.h new file mode 100644 index 0000000..963ff55 --- /dev/null +++ b/Odometry/code/motor_control.h @@ -0,0 +1,71 @@ +#ifndef MOTOR_CONTROL_H +#define MOTOR_CONTROL_H + +#include +#include "pins.h" + +void setupMotors() +{ + pinMode(RRPWM, OUTPUT); + pinMode(RLPWM, OUTPUT); + pinMode(LRPWM, OUTPUT); + pinMode(LLPWM, OUTPUT); + pinMode(REN, OUTPUT); + pinMode(LEN, OUTPUT); + pinMode(WRPWM, OUTPUT); + pinMode(WLPWM, OUTPUT); + pinMode(WEN, OUTPUT); + + digitalWrite(REN, HIGH); + digitalWrite(LEN, HIGH); + digitalWrite(WEN, HIGH); +} + +void controlMotors(int forwardVelocity, int turnVelocity) +{ + int leftSpeed = forwardVelocity - turnVelocity; // Adjust left wheel + int rightSpeed = forwardVelocity + turnVelocity; // Adjust right wheel + + leftSpeed = constrain(leftSpeed, -255, 255); + rightSpeed = constrain(rightSpeed, -255, 255); + + // Left wheel control + if (leftSpeed > 0) + { + analogWrite(LLPWM, 0); + analogWrite(LRPWM, leftSpeed); + } + else + { + analogWrite(LLPWM, -leftSpeed); + analogWrite(LRPWM, 0); + } + + // Right wheel control + if (rightSpeed > 0) + { + analogWrite(RLPWM, 0); + analogWrite(RRPWM, rightSpeed); + } + else + { + analogWrite(RLPWM, -rightSpeed); + analogWrite(RRPWM, 0); + } +} + +void controlWeapon(int weaponVelocity) +{ + if (weaponVelocity > 0) + { + analogWrite(WLPWM, 0); + analogWrite(WRPWM, weaponVelocity); + } + else + { + analogWrite(WLPWM, -weaponVelocity); + analogWrite(WRPWM, 0); + } +} + +#endif diff --git a/Odometry/code/pins.h b/Odometry/code/pins.h new file mode 100644 index 0000000..9580d82 --- /dev/null +++ b/Odometry/code/pins.h @@ -0,0 +1,33 @@ +#ifndef PINS_H +#define PINS_H + +// Receiver Input Pins +#define S_BUS_IN 16 + +// BTS7960 Motor Driver Pins (Wheels) (Right) +#define RRPWM 25 +#define RLPWM 26 +#define REN 33 + +// BTS7960 Motor Driver Pins (Wheels) (Left) +#define LRPWM 18 +#define LLPWM 19 +#define LEN 21 + +// Weapon Motor Pins +#define WLPWM 12 +#define WRPWM 14 +#define WEN 27 + +#define NOISE_THRESHOLD 15 // Ignore small values < 15 in PWM + +#define THROTTLE_CHANNEL 1 +#define STEERING_CHANNEL 0 +#define WEAPON_CHANNEL 2 +#define KILL_SWITCH_CHANNEL 5 // Channel 6 (zero-based index) +#define WEAPON_STATE_CHANNEL 6 // Channel 7 +#define STEERING_INVERT_CHANNEL 7 // Channel 8 + +#define TIMEOUT_MS 500 // Stop bot if no SBUS data received in 500ms + +#endif \ No newline at end of file diff --git a/Odometry/code/receiver.h b/Odometry/code/receiver.h new file mode 100644 index 0000000..95975d4 --- /dev/null +++ b/Odometry/code/receiver.h @@ -0,0 +1,19 @@ +#ifndef RECEIVER_H +#define RECEIVER_H + +#include "sbus.h" +#include + +bfs::SbusRx sbus_rx(&Serial2, S_BUS_IN, -1, true); +bfs::SbusData data; + +void setupReciever() +{ + /* Start SBUS communication */ + sbus_rx.Begin(); + Serial.println("SBUS Receiver Started!"); +} + + + +#endif \ No newline at end of file diff --git a/Odometry/code/restart.h b/Odometry/code/restart.h new file mode 100644 index 0000000..7753298 --- /dev/null +++ b/Odometry/code/restart.h @@ -0,0 +1,55 @@ +#ifndef RESTART_H +#define RESTART_H + +#include "receiver.h" +#include "pins.h" +#include + +#define TOGGLE_COUNT 3 // Number of toggles required +#define TIMEOUT_MS 2000 // Time window in milliseconds + +void restart() +{ + int toggleCount = 0; + unsigned long startTime = millis(); + bool lastKillState = false; // Store last state of kill switch + + Serial.println("🔄 Restart mode activated. Toggle kill switch to restart."); + + while (true) // Stay here until restart + { + if (sbus_rx.Read()) // Check if SBUS data is available + { + data = sbus_rx.data(); + bool killSwitch = (data.ch[KILL_SWITCH_CHANNEL] > 1000); // CH6: Kill switch + + if (killSwitch != lastKillState) // Detect a toggle + { + toggleCount++; + lastKillState = killSwitch; + Serial.print("Kill switch toggled: "); + Serial.println(toggleCount); + } + + // Restart the system if toggle count met within time window + if (toggleCount >= TOGGLE_COUNT && millis() - startTime <= TIMEOUT_MS) + { + Serial.println("🔄 Restarting system..."); + delay(100); // Small delay before reset + ESP.restart(); // Safe reset for ESP32 + } + } + + // If time expired, reset counter but continue listening + if (millis() - startTime > TIMEOUT_MS) + { + toggleCount = 0; // Reset toggle count + startTime = millis(); // Reset timer + Serial.println("⏳ Time expired. Restart attempt reset. Keep toggling..."); + } + + delay(1); // Prevents watchdog timeout + } +} + +#endif // RESTART_H diff --git a/Odometry/drdy_spi/drdy_spi.ino b/Odometry/drdy_spi/drdy_spi.ino new file mode 100644 index 0000000..587ae11 --- /dev/null +++ b/Odometry/drdy_spi/drdy_spi.ino @@ -0,0 +1,40 @@ +#include +#include + +MPU9250_asukiaaa mySensor; + +void setup() { + Serial.begin(115200); + Wire.begin(); + + mySensor.setWire(&Wire); + mySensor.beginAccel(); + mySensor.beginGyro(); + //mySensor.beginMag(); + + Serial.println("MPU9250 Raw Data (No Calibration)"); +} + +void loop() { + mySensor.accelUpdate(); + mySensor.gyroUpdate(); + mySensor.magUpdate(); + + Serial.print("Accel X/Y/Z: "); + Serial.print(mySensor.accelX()); Serial.print(", "); + Serial.print(mySensor.accelY()); Serial.print(", "); + Serial.println(mySensor.accelZ()); + + Serial.print("Gyro X/Y/Z: "); + Serial.print(mySensor.gyroX()); Serial.print(", "); + Serial.print(mySensor.gyroY()); Serial.print(", "); + Serial.println(mySensor.gyroZ()); + + Serial.print("Mag X/Y/Z: "); + Serial.print(mySensor.magX()); Serial.print(", "); + Serial.print(mySensor.magY()); Serial.print(", "); + Serial.println(mySensor.magZ()); + + Serial.println("------"); + delay(500); // Slow down the loop +} diff --git a/Odometry/imu_and_optical_flow/imu_and_optical_flow.ino b/Odometry/imu_and_optical_flow/imu_and_optical_flow.ino new file mode 100644 index 0000000..bcf182d --- /dev/null +++ b/Odometry/imu_and_optical_flow/imu_and_optical_flow.ino @@ -0,0 +1,117 @@ +#include "Bitcraze_PMW3901.h" + +#include +#include +#include +#include +//#include + +#define BNO055_SAMPLERATE_DELAY_MS (100) + +// Check I2C device address and correct line below (by default address is 0x29 or 0x28) +// id, address +Adafruit_BNO055 bno = Adafruit_BNO055(55, 0x29); + +// Using digital pin 10 for chip select +Bitcraze_PMW3901 flow(5); + +float yaw,pitch,roll; +float dx_world, dy_world; +float dx_raw,dy_raw; +float x_new, y_new; + +struct SensorData { + int16_t deltaX; + int16_t deltaY; + float yaw; + float x_new; + float y_new; +}; + +void printSensorData(const SensorData& data) { + Serial.print("deltaX: "); + Serial.print(data.deltaX); + Serial.print(", deltaY: "); + Serial.print(data.deltaY); + Serial.print(", yaw: "); + Serial.print(data.yaw); + Serial.print(", x_new: "); + Serial.print(data.x_new); + Serial.print(", y_new: "); + Serial.println(data.y_new); +} + +void setup() { + Serial.begin(115200); + + if (!flow.begin()) { + Serial.println("Initialization of the flow sensor failed"); + while(1) { } + } + if(!bno.begin()) + { + /* There was a problem detecting the BNO055 ... check your connections */ + Serial.print("Ooops, no BNO055 detected ... Check your wiring or I2C ADDR!"); + while(1); + } + + delay(1000); + + /* Use external crystal for better accuracy */ + bno.setExtCrystalUse(true); +} + +int16_t deltaX,deltaY; + +void loop() { + // Get motion count since last call + flow.readMotionCount(&deltaX, &deltaY); + + // Serial.print("X: "); + // Serial.print(deltaX); + // Serial.print(", Y: "); + // Serial.print(deltaY); + // Serial.print("\n"); + + sensors_event_t event; + bno.getEvent(&event); + + yaw = event.orientation.x; + pitch = event.orientation.y; + roll = event.orientation.z; + + // Serial.print(F("Orientation: x: ")); + // Serial.print(yaw); + // Serial.print(F(" y: ")); + // Serial.print(pitch); + // Serial.print(F(" z: ")); + // Serial.print(roll); + // Serial.println(F("")); + + + float yaw_rad = yaw * PI / 180.0; + + dx_world = deltaX * cos(yaw_rad) - deltaY * sin(yaw_rad); + dy_world = deltaX * sin(yaw_rad) + deltaY * cos(yaw_rad); + + + x_new = dx_world; + y_new = dy_world; + + + // Serial.print("displacement x: "); + // Serial.print(x_new); + // Serial.print(F(" y: ")); + // Serial.println(y_new); + +SensorData data; +data.deltaX = deltaX; +data.deltaY = deltaY; +data.yaw = yaw; +data.x_new = x_new; +data.y_new = y_new; + +printSensorData(data); + + delay(100); +} \ No newline at end of file