Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
72 changes: 72 additions & 0 deletions Odometry/code/code.ino
Original file line number Diff line number Diff line change
@@ -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 <Arduino.h>
#if defined(ESP8266)
#include <ESP8266WiFi.h>
#include <ESPAsyncTCP.h>
#elif defined(ESP32)
#include <AsyncTCP.h>
#include <WiFi.h>
#endif
#include <DNSServer.h>
#include <ESPAsyncWebServer.h>
#include <WString.h>
#include <MycilaWebSerial.h>

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();
}
}
Binary file added Odometry/code/data/ESPAsyncWebServer.zip
Binary file not shown.
71 changes: 71 additions & 0 deletions Odometry/code/motor_control.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,71 @@
#ifndef MOTOR_CONTROL_H
#define MOTOR_CONTROL_H

#include <Arduino.h>
#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
33 changes: 33 additions & 0 deletions Odometry/code/pins.h
Original file line number Diff line number Diff line change
@@ -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
19 changes: 19 additions & 0 deletions Odometry/code/receiver.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
#ifndef RECEIVER_H
#define RECEIVER_H

#include "sbus.h"
#include <Arduino.h>

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
55 changes: 55 additions & 0 deletions Odometry/code/restart.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,55 @@
#ifndef RESTART_H
#define RESTART_H

#include "receiver.h"
#include "pins.h"
#include <Arduino.h>

#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
40 changes: 40 additions & 0 deletions Odometry/drdy_spi/drdy_spi.ino
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
#include <Wire.h>
#include <MPU9250_asukiaaa.h>

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
}
Loading