diff --git a/.gitignore b/.gitignore index e77605f..00aa959 100644 --- a/.gitignore +++ b/.gitignore @@ -1,5 +1,6 @@ # Local scripts liner.py +TODO.md tests/control_tests .build/ review/ diff --git a/CMakeLists.txt b/CMakeLists.txt index 1d5d348..36cc98e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,21 +1,4 @@ -set(PROBOT_SRCS - src/core/runtime.cpp - src/core/scheduler.cpp - src/core/wdt.cpp - src/io/ui_input.cpp - src/platform/esp32s3/drivers/builtin_led_ws2812.cpp - src/probot/devices/motors/Boardoza_BA6208.cpp - src/probot/devices/motors/boardoza_ba6208_driver.cpp - src/probot/devices/motors/boardoza_vnh_motor_driver.cpp - src/probot/logging/logger.cpp - src/probot/logging/telemetry_profiles.cpp - src/probot/logging/wifi_transport_esp32.cpp - src/probot/robot/system.cpp - src/probot/sensors/imu/mpu6050.cpp -) - idf_component_register( - SRCS ${PROBOT_SRCS} INCLUDE_DIRS "src" REQUIRES arduino ) diff --git a/FUTURE_WORK.md b/FUTURE_WORK.md index 157c484..4e6a153 100644 --- a/FUTURE_WORK.md +++ b/FUTURE_WORK.md @@ -5,7 +5,7 @@ - Boardoza motor kontrolcüsü desteğini entegre et (donanım ekibinden gelecek PWM/CAN detayları bekleniyor). - ESP32-S3 için donanımsal quadrature encoder sürücüsü ekle (temel örnek: PCNT + 1024 CPR tekerlek). - IMotorController arayüzünü PIDF + feedforward slotları ve isteğe bağlı motion profile zamanlaması (trapez/S-eğrisi) ile genişlet. -- NFR örneklerinde kullanılan NullMotorController yer tutucularını gerçek IMotorController uygulamalarıyla değiştir. +- NFR örneklerinde kullanılan NullIMotorController yer tutucularını gerçek IMotorController uygulamalarıyla değiştir. - Her aktarma için motor motion profile ve feedforward ön ayarlarını yapılandıracak şasi seviyesinde yardımcı fonksiyonlar sun. - MPU6050 entegrasyonunu sağlamlaştır (kalibrasyon akışı, hata yönetimi) ve ilerideki MPU9050/BNO varyantlarına hazırlık yap. - Robotlar hazır olduğunda joystick hattını donanım üzerinde 10 ms örnekleme + 20 ms kontrol döngüsü ile doğrula. @@ -24,7 +24,7 @@ - Integrate Boardoza motor controller support (PWM/CAN specifics pending from hardware team). - Add hardware quadrature encoder driver implementation for ESP32-S3 (baseline example: PCNT + 1024 CPR wheel). - Extend IMotorController to PIDF + feedforward slots and optional motion profile scheduling (trapezoid/S-curve). -- Swap placeholder NullMotorController usages with real IMotorController implementations in NFR examples. +- Swap placeholder NullIMotorController usages with real IMotorController implementations in NFR examples. - Expose chassis-level helpers to configure motor motion profiles and feedforward presets per drivetrain. - Harden MPU6050 integration (calibration flow, failure handling) and prepare for future MPU9050/BNO variants. - Validate joystick pipeline at 10 ms sampling + 20 ms control loop on hardware once robots are available. diff --git a/Makefile b/Makefile index 9430c0b..4b64a7b 100644 --- a/Makefile +++ b/Makefile @@ -12,22 +12,22 @@ VERSION_SYNC_SCRIPT := $(CURDIR)/tools/sync_version.py # Examples EXAMPLES_DIR := $(CURDIR)/examples -EXAMPLES_LIST := $(filter-out __library_impl,$(notdir $(wildcard $(EXAMPLES_DIR)/*))) +EXAMPLE_SKETCHES := $(shell find $(EXAMPLES_DIR) -maxdepth 3 -mindepth 1 -name "*.ino") +EXAMPLES_LIST := $(sort $(patsubst %/,%,$(patsubst $(EXAMPLES_DIR)/%,%,$(dir $(EXAMPLE_SKETCHES))))) +EXAMPLES_LIST := $(filter-out __library_impl __library_impl/%,$(EXAMPLES_LIST)) DEFAULT_EXAMPLE := $(firstword $(EXAMPLES_LIST)) EXAMPLE ?= $(DEFAULT_EXAMPLE) BUILD_DIR_BASE := $(CURDIR)/.build TEST_STUB_DIR := $(CURDIR)/tests/stubs TEST_SOURCES := $(filter %.cpp,$(wildcard $(CURDIR)/tests/*.cpp)) -TEST_EXTRA_SOURCES := \ - $(CURDIR)/src/probot/logging/logger.cpp \ - $(CURDIR)/src/probot/logging/telemetry_profiles.cpp +TEST_EXTRA_SOURCES := # Common flags -EXTRA_FLAGS_COMMON := -DESP32S3 -DARDUINO_USB_MODE=1 -DARDUINO_USB_CDC_ON_BOOT=1 +EXTRA_FLAGS_COMMON := -DESP32S3 -DARDUINO_USB_MODE=1 # Example-specific extra flags (function) -example_flags = $(if $(filter LoopPeriodStress,$(1)),-DPROBOT_CLM_NOLOG=1 -DPROBOT_SCHED_NOLOG=1,) +example_flags = $(if $(filter LoopPeriodStress,$(notdir $(1))),-DPROBOT_CLM_NOLOG=1 -DPROBOT_SCHED_NOLOG=1,) .PHONY: all build build-all _build_single upload clean boards libs serial list help test tests/control_tests @@ -90,7 +90,7 @@ version-sync: $(PYTHON) $(VERSION_SYNC_SCRIPT) tests/control_tests: $(TEST_SOURCES) - g++ -std=c++17 -Wall -Wextra -pedantic -I src -I $(TEST_STUB_DIR) -DPROBOT_CLM_NOLOG=1 -DPROBOT_SCHED_NOLOG=1 -DPROBOT_LOGGER_NO_SCHED_ATTACH=1 -o $@ $(TEST_SOURCES) $(TEST_EXTRA_SOURCES) + g++ -std=c++17 -Wall -Wextra -pedantic -I src -I $(TEST_STUB_DIR) -DPROBOT_CLM_NOLOG=1 -DPROBOT_SCHED_NOLOG=1 -DPROBOT_LOGGER_NO_SCHED_ATTACH=1 -DPROBOT_BUILTINLED_EXTERNAL=1 -o $@ $(TEST_SOURCES) $(TEST_EXTRA_SOURCES) test: build tests/control_tests ./tests/control_tests diff --git a/README.md b/README.md index ba07ee0..127833c 100644 --- a/README.md +++ b/README.md @@ -1,6 +1,6 @@ # Probot Lib -MEB robot yarışmaları için geliştirilmiş Arduino kütüphanesi. PID kontrolü, motion profiling, WiFi sürücü istasyonu ve ESP32-S3 desteği ile geliyor. +MEB robot yarışmaları için geliştirilmiş Arduino kütüphanesi. PID kontrolü, WiFi sürücü istasyonu ve ESP32-S3 desteği ile geliyor. **Tüm dokümantasyon için:** https://docs.probotstudio.com/yazilim/ @@ -12,7 +12,7 @@ MEB robot yarışmaları için geliştirilmiş Arduino kütüphanesi. PID kontro Arduino IDE'nin Library Manager'ından "Probot Lib" arayıp yükleyin. **İlk robot kodunuz:** -1. `File → Examples → Probot Lib → BasicTankDrive` açın +1. `File → Examples → Probot Lib → command_based → TankDriveDemo` açın 2. ESP32-S3'e yükleyin 3. `Probot-XXXX` WiFi ağına bağlanın 4. Tarayıcıdan `http://192.168.4.1` adresini açın @@ -25,16 +25,16 @@ Arduino IDE'nin Library Manager'ından "Probot Lib" arayıp yükleyin. Kütüphane seviyelerine göre düzenlenmiş örneklerle geliyor: **Başlangıç seviyesi:** -- `BasicTankDrive` - Tank sürüş sistemi ve joystick kontrolü -- `MotorTest` - Motor test ve kalibrasyon +- `command_based/TankDriveDemo` - Tank sürüş sistemi ve joystick kontrolü +- `MotorOpenLoopDemo` - Motor kontrolcu test ve kalibrasyonu **Orta seviye:** -- `ClosedLoopMotorTest` - PID tabanlı hız kontrolü -- `TankDriveAuto` - Otonom hareket (mesafe ve dönüş) +- `MotorControllerDemo` - PID tabanlı hız kontrolü (PidMotorWrapper) +- `command_based/AutonomousDemo` - Otonom hareket (mesafe ve dönüş) **İleri seviye:** -- `FullRobotDemo` - Tam donanımlı robot (sürüş + mekanizmalar) -- `nfr/AdvancedTankDrive` - Trajectory following ve motion profiling +- `command_based/MecanumDriveDemo` - Mecanum sürüş ve kinematik kontrol +- `ShooterDemo` - Kapalı çevrim atıcı kontrolü Her örnek doğrudan çalışır durumda ve yorumlarla açıklanmıştır. @@ -42,7 +42,7 @@ Her örnek doğrudan çalışır durumda ve yorumlarla açıklanmıştır. ## Platform Desteği -- **Arduino IDE / arduino-cli:** `library.properties` ve `Makefile` üzerinden doğrudan desteklenir. `make build EXAMPLE=TankDriveDemo` komutu, `arduino-cli` ile örnekleri derler. +- **Arduino IDE / arduino-cli:** `library.properties` ve `Makefile` üzerinden doğrudan desteklenir. `make build EXAMPLE=command_based/TankDriveDemo` komutu, `arduino-cli` ile örnekleri derler. - **PlatformIO (Arduino framework):** Kütüphaneyi `lib_deps = /path/to/probot-lib` ya da Git URL'siyle ekleyin. `library.json` sürüm bilgisi `VERSION` dosyasından otomatik güncellenir. - **ESP-IDF + Arduino bileşeni:** Depoyu IDF projenizin `components/` klasörüne yerleştirip `idf.py build` çalıştırabilirsiniz. `idf_component.yml` otomatik olarak Arduino bileşenine bağımlıdır; `app_main` içinde `probot::runtime_setup()` çağırarak Arduino dışındaki uygulamalarda da aynı robot yaşam döngüsünü başlatabilirsiniz. @@ -54,7 +54,7 @@ Tüm platformlarda sürüm numarası `VERSION` dosyasından yönetilir; `make ve Kütüphane şunları sağlar: - WiFi tabanlı driver station (web arayüzü) -- PID, feedforward ve motion profiling +- PID ve feedforward - State-space kontrol araçları (Kalman filtre, LQR) - Tank ve mecanum sürüş soyutlamaları - Mekanizma yardımcıları (kol, asansör, slider) @@ -68,7 +68,7 @@ Detaylı API dokümantasyonu ve kullanım örnekleri için https://docs.probotst **Önerilen:** [Boardoza Pulse S32-S3](https://boardoza.com/product/boardoza-pulse-s32-s3-breakout-board/) -Kütüphane ESP32-S3 için geliştirilmiştir. Motor sürücü olarak herhangi bir PWM sürücü kullanabilirsiniz (Boardoza BA6208, TB6612, vb.) +Kütüphane ESP32-S3 için geliştirilmiştir. Motor kontrolcusu olarak herhangi bir PWM kontrolcu kullanabilirsiniz (Boardoza VNH5019, BTS7960B, TB6612, vb.) --- @@ -108,7 +108,7 @@ Amacımız ekiplerin yarışma gününe hazır robotlarla çıkmasını sağlama # Probot Lib (EN) -Arduino library built for Ministry of Education robot competitions. Includes PID control, motion profiling, a WiFi driver station, and ESP32-S3 support. +Arduino library built for Ministry of Education robot competitions. Includes PID control, a WiFi driver station, and ESP32-S3 support. **Full documentation:** https://docs.probotstudio.com/yazilim/ @@ -120,7 +120,7 @@ Arduino library built for Ministry of Education robot competitions. Includes PID Open the Arduino IDE Library Manager, search for "Probot Lib", and install it. **Your first robot code:** -1. Open `File → Examples → Probot Lib → BasicTankDrive` +1. Open `File → Examples → Probot Lib → command_based → TankDriveDemo` 2. Upload it to the ESP32-S3 3. Connect to the `Probot-XXXX` WiFi network 4. Visit `http://192.168.4.1` in your browser @@ -133,16 +133,16 @@ Open the Arduino IDE Library Manager, search for "Probot Lib", and install it. The library ships with examples organized by proficiency level: **Beginner level:** -- `BasicTankDrive` - Tank drive system with joystick control -- `MotorTest` - Motor testing and calibration +- `command_based/TankDriveDemo` - Tank drive system with joystick control +- `MotorOpenLoopDemo` - Motor controller open-loop test and calibration **Intermediate:** -- `ClosedLoopMotorTest` - PID-based speed control -- `TankDriveAuto` - Autonomous motion (distance and turn) +- `MotorControllerDemo` - PID-based speed control (PidMotorWrapper) +- `command_based/AutonomousDemo` - Autonomous motion (distance and turn) **Advanced:** -- `FullRobotDemo` - Full-featured robot (drive + mechanisms) -- `nfr/AdvancedTankDrive` - Trajectory following and motion profiling +- `command_based/MecanumDriveDemo` - Mecanum drive and kinematic control +- `ShooterDemo` - Closed-loop shooter control Every example runs out of the box and is documented with inline comments. @@ -150,7 +150,7 @@ Every example runs out of the box and is documented with inline comments. ## Platform Support -- **Arduino IDE / arduino-cli:** build examples with `make build EXAMPLE=TankDriveDemo`; metadata comes from `library.properties`. +- **Arduino IDE / arduino-cli:** build examples with `make build EXAMPLE=command_based/TankDriveDemo`; metadata comes from `library.properties`. - **PlatformIO (Arduino framework):** add `lib_deps = /path/to/probot-lib` or the Git URL; `library.json` stays in sync with `VERSION`. - **ESP-IDF with the Arduino component:** drop the repository under your project's `components/` directory (or use `idf_component.yml` via the component manager) and call `idf.py build`. Invoke `probot::runtime_setup()` from `app_main()` to reuse the Arduino lifecycle on pure ESP-IDF projects. @@ -162,7 +162,7 @@ Every example runs out of the box and is documented with inline comments. The library provides: - WiFi-based driver station (web interface) -- PID, feedforward, and motion profiling utilities +- PID and feedforward utilities - State-space control tools (Kalman filter, LQR) - Tank and mecanum drive abstractions - Mechanism helpers (arm, elevator, slider) @@ -176,7 +176,7 @@ For in-depth API docs and usage guides, visit https://docs.probotstudio.com/yazi **Recommended:** [Boardoza Pulse S32-S3](https://boardoza.com/product/boardoza-pulse-s32-s3-breakout-board/) -The library targets the ESP32-S3. You can use any PWM motor driver (Boardoza BA6208, TB6612, etc.). +The library targets the ESP32-S3. You can use any PWM motor controller board (Boardoza VNH5019, BTS7960B, TB6612, etc.). --- diff --git a/VERSION b/VERSION index 845639e..0ea3a94 100644 --- a/VERSION +++ b/VERSION @@ -1 +1 @@ -0.1.4 +0.2.0 diff --git a/examples/AutonomousDemo/AutonomousDemo.ino b/examples/AutonomousDemo/AutonomousDemo.ino deleted file mode 100644 index 1da665d..0000000 --- a/examples/AutonomousDemo/AutonomousDemo.ino +++ /dev/null @@ -1,137 +0,0 @@ -#include -#include -#include -#include -#include -#include - -// Otonom tank demo için iki adet VNH sürücüsü. -static constexpr int L_INA = 33; -static constexpr int L_INB = 34; -static constexpr int L_PWM = 35; -static constexpr int L_ENA = -1; -static constexpr int L_ENB = -1; - -static constexpr int R_INA = 36; -static constexpr int R_INB = 37; -static constexpr int R_PWM = 38; -static constexpr int R_ENA = -1; -static constexpr int R_ENB = -1; - -static probot::motor::BoardozaVNHMotorDriver leftDriver(L_INA, L_INB, L_PWM, L_ENA, L_ENB); -static probot::motor::BoardozaVNHMotorDriver rightDriver(R_INA, R_INB, R_PWM, R_ENA, R_ENB); -static probot::sensors::NullEncoder leftEncoder; -static probot::sensors::NullEncoder rightEncoder; - -static const probot::control::PidConfig kPid{.kp = 0.32f, .ki = 0.015f, .kd = 0.0f, .kf = 0.0f, - .out_min = -1.0f, .out_max = 1.0f}; -static probot::control::PID pidLeft(kPid); -static probot::control::PID pidRight(kPid); -static probot::control::ClosedLoopMotor motorLeft(&leftEncoder, &pidLeft, &leftDriver, 1.0f, 1.0f); -static probot::control::ClosedLoopMotor motorRight(&rightEncoder, &pidRight, &rightDriver, 1.0f, 1.0f); -static probot::drive::BasicTankDrive chassis(&motorLeft, &motorRight); - -PROBOT_SET_DRIVER_STATION_PASSWORD("ProBot1234"); - -enum class AutoStep { - kDriveForward, - kPause, - kTurn, - kDriveToGoal, - kFinished -}; - -static AutoStep g_step = AutoStep::kDriveForward; -static uint32_t g_stepStart = 0; - -void robotInit() { - Serial.begin(115200); - delay(100); - - leftDriver.begin(); - rightDriver.begin(); - leftDriver.setBrakeMode(true); - rightDriver.setBrakeMode(true); - - motorLeft.setTimeoutMs(0); - motorRight.setTimeoutMs(0); - - chassis.setWheelCircumference(32.0f); - chassis.setTrackWidth(29.0f); - - Serial.println("[AutonomousDemo] robotInit: Otonom örneği hazır"); -} - -void robotEnd() { - chassis.setVelocity(0.0f, 0.0f); - Serial.println("[AutonomousDemo] robotEnd: Motorlar durdu"); -} - -void teleopInit() { - Serial.println("[AutonomousDemo] teleopInit: Bu örnekte teleop, tank sürüşü sağlar"); -} - -void teleopLoop() { - auto js = probot::io::joystick_api::makeDefault(); - float left = js.getLeftY() * 100.0f; - float right = js.getRightY() * 100.0f; - chassis.setVelocity(left, right); - chassis.update(millis(), 20); - delay(20); -} - -void autonomousInit() { - Serial.println("[AutonomousDemo] autonomousInit: İleri -> Bekle -> 90° dön -> Hedefe git"); - g_step = AutoStep::kDriveForward; - g_stepStart = millis(); - chassis.driveDistance(80.0f); // 80 cm ileri -} - -void autonomousLoop() { - uint32_t now = millis(); - - switch (g_step) { - case AutoStep::kDriveForward: - if (now - g_stepStart > 2500) { - g_step = AutoStep::kPause; - g_stepStart = now; - chassis.setVelocity(0.0f, 0.0f); - Serial.println("[AutonomousDemo] Duraklama"); - } - break; - - case AutoStep::kPause: - if (now - g_stepStart > 800) { - g_step = AutoStep::kTurn; - g_stepStart = now; - chassis.turnDegrees(90.0f); - Serial.println("[AutonomousDemo] 90 derece dönüş başlıyor"); - } - break; - - case AutoStep::kTurn: - if (now - g_stepStart > 2200) { - g_step = AutoStep::kDriveToGoal; - g_stepStart = now; - chassis.driveDistance(40.0f); - Serial.println("[AutonomousDemo] Hedefe son itiş"); - } - break; - - case AutoStep::kDriveToGoal: - if (now - g_stepStart > 2000) { - g_step = AutoStep::kFinished; - chassis.setVelocity(0.0f, 0.0f); - Serial.println("[AutonomousDemo] Otonom tamamlandı"); - } - break; - - case AutoStep::kFinished: - default: - chassis.setVelocity(0.0f, 0.0f); - break; - } - - chassis.update(now, 20); - delay(20); -} diff --git a/examples/IBT2MotorDemo/IBT2MotorDemo.ino b/examples/IBT2MotorDemo/IBT2MotorDemo.ino new file mode 100644 index 0000000..508378c --- /dev/null +++ b/examples/IBT2MotorDemo/IBT2MotorDemo.ino @@ -0,0 +1,152 @@ +/** + * IBT2MotorDemo - IBT-2 (BTS7960) motor surucu dogrudan kontrol ornegi + * + * !! UYARI !! + * Bu ornek probot driver siniflarini KULLANMAZ. + * Dogrudan ESP32 PWM ve GPIO ile motor kontrol eder. + * Herhangi bir sorun yasarsaniz probot kutuphanesi sorumluluk almaz. + * Kendi riskinizle kullanin. + * + * ============================================================================ + * VOLTAJ UYUMSUZLUGU - ONEMLI! + * ============================================================================ + * - IBT-2 modulu 5V mantik seviyesi ile calisir + * - ESP32 GPIO cikislari 3.3V seviyesindedir + * - Cogu IBT-2 modulu 3.3V sinyali kabul eder, AMA garanti degildir + * - Guvenli kullanim icin LOGIC LEVEL CONVERTER (3.3V -> 5V) onerılır + * - Logic converter kullanmazsaniz modül duzgun calismayabilir + * + * ============================================================================ + * KONTROL MANTIGI + * ============================================================================ + * Bu ornekte kullanilan kontrol sekli: + * - RPWM: Ileri yon PWM (0-255) + * - LPWM: Geri yon PWM (0-255) + * - Ileri gitmek icin: RPWM=PWM, LPWM=0 + * - Geri gitmek icin: RPWM=0, LPWM=PWM + * - Durmak icin: RPWM=0, LPWM=0 + * + * Bazi motor suruculer farkli mantik kullanir: + * - DIR + PWM (tek PWM, ayri yon pini) + * - IN1 + IN2 + PWM (H-koprusu kontrolu) + * - IN1 + IN2 (PWM dahili) + * + * Sizin motor surucunuz farkli calisiyorsa setMotorPower() fonksiyonunu + * kendi ihtiyaciniza gore degistirin. + * + * ============================================================================ + * IBT-2 BAGLANTI SEMASI + * ============================================================================ + * IBT-2 Pin | ESP32 Pin | Aciklama + * -----------|-------------|---------------------------------- + * RPWM | GPIO 5 | Ileri PWM (veya kendi pininiz) + * LPWM | GPIO 6 | Geri PWM (veya kendi pininiz) + * R_EN | 3.3V/5V | Sag enable (her zaman aktif) + * L_EN | 3.3V/5V | Sol enable (her zaman aktif) + * VCC | 5V | Mantik beslemesi + * GND | GND | Ortak toprak + * B+/B- | Motor | Motor baglantisi + * M+/M- | Guc kaynagi| Motor guc beslemesi (12V-24V) + * + * ============================================================================ + */ + +#define PROBOT_WIFI_AP_PASSWORD "ProBot1234" + +#include +#include + +// ============================================================================ +// PIN KONFIGURASYONU - Kendi kartiniza gore degistirin! +// ============================================================================ +static constexpr int PIN_RPWM = 5; // Ileri PWM pini +static constexpr int PIN_LPWM = 6; // Geri PWM pini + +// ============================================================================ +// PWM KONFIGURASYONU +// ============================================================================ +static constexpr int PWM_FREQ = 20000; // 20kHz (motor gurultusu azaltir) +static constexpr int PWM_RESOLUTION = 8; // 8-bit (0-255 aralik) + +// Motor durumu +static float g_power = 0.0f; + +/** + * Motor gucunu ayarla + * + * @param power -1.0 (tam geri) ile 1.0 (tam ileri) arasinda + * + * NOT: Bu fonksiyon IBT-2 icin yazilmistir. + * Farkli motor surucu kullaniyorsaniz bu fonksiyonu degistirin. + */ +void setMotorPower(float power) { + // -1.0 ile 1.0 arasinda sinirla + power = constrain(power, -1.0f, 1.0f); + g_power = power; + + // PWM degerini hesapla (0-255) + int pwmValue = abs(power) * 255; + + if (power > 0.01f) { + // Ileri: RPWM aktif, LPWM 0 + ledcWrite(PIN_RPWM, pwmValue); + ledcWrite(PIN_LPWM, 0); + } else if (power < -0.01f) { + // Geri: LPWM aktif, RPWM 0 + ledcWrite(PIN_RPWM, 0); + ledcWrite(PIN_LPWM, pwmValue); + } else { + // Durdur: Her iki PWM 0 + ledcWrite(PIN_RPWM, 0); + ledcWrite(PIN_LPWM, 0); + } +} + +void robotInit() { + Serial.begin(115200); + delay(100); + + // ESP32 LEDC PWM kurulumu + ledcAttach(PIN_RPWM, PWM_FREQ, PWM_RESOLUTION); + ledcAttach(PIN_LPWM, PWM_FREQ, PWM_RESOLUTION); + + // Baslangicta durdur + setMotorPower(0.0f); + + Serial.println("============================================"); + Serial.println("[IBT2MotorDemo] UYARI: Driver-siz ornek!"); + Serial.println("Sorun yasarsaniz probot sorumluluk almaz."); + Serial.println("============================================"); + Serial.printf(" RPWM pin: %d, LPWM pin: %d\n", PIN_RPWM, PIN_LPWM); + Serial.printf(" PWM freq: %d Hz, resolution: %d-bit\n", PWM_FREQ, PWM_RESOLUTION); + Serial.println(" Logic level converter kullanmaniz onerilir!"); +} + +void robotEnd() { + setMotorPower(0.0f); + Serial.println("[IBT2MotorDemo] Motor durduruldu"); +} + +void teleopInit() { + Serial.println("[IBT2MotorDemo] Sol stick Y ile motor kontrol"); +} + +void teleopLoop() { + auto js = probot::io::joystick_api::makeDefault(); + + float power = js.getLeftY(); + setMotorPower(power); + + probot::telemetry::printf("IBT2: %.2f\n", g_power); + Serial.printf("[IBT2] power=%.2f\n", g_power); + + delay(50); +} + +void autonomousInit() { + setMotorPower(0.0f); +} + +void autonomousLoop() { + delay(50); +} diff --git a/examples/JoystickTest/JoystickTest.ino b/examples/JoystickTest/JoystickTest.ino index a932644..3b07e14 100644 --- a/examples/JoystickTest/JoystickTest.ino +++ b/examples/JoystickTest/JoystickTest.ino @@ -1,72 +1,206 @@ +/** + * JoystickTest - Joystick veri okuma örneği + * + * Bu örnek DriverStation uygulamasından gelen joystick verilerini + * seri port üzerinden yazdırır. Motor veya başka donanım kullanmaz. + * + * ============================================================================ + * NE ÖĞRENECEKSINIZ? + * ============================================================================ + * - joystick_api arayüzünün kullanımı + * - Analog eksenlerin okunması (stick'ler, tetikler) + * - Dijital butonların okunması (A, B, X, Y, bumper'lar) + * - D-pad (POV) değerinin okunması + * - Sequence numarasıyla veri güncelliğini kontrol etme + * + * ============================================================================ + * JOYSTICK API GENEL BAKIŞ + * ============================================================================ + * probot::io::joystick_api::makeDefault() ile varsayılan joystick'e + * erişirsiniz. Bu fonksiyon bir JoystickData nesnesi döner. + * + * ANALOG EKSENLER (float, -1.0 ile 1.0 arası): + * getLeftX() - Sol stick X ekseni (sola=-1, sağa=+1) + * getLeftY() - Sol stick Y ekseni (geri=-1, ileri=+1) + * getRightX() - Sağ stick X ekseni + * getRightY() - Sağ stick Y ekseni + * + * TETİKLER (float, 0.0 ile 1.0 arası): + * getLeftTriggerAxis() - Sol tetik (LT/L2) + * getRightTriggerAxis() - Sağ tetik (RT/R2) + * + * DİJİTAL BUTONLAR (bool): + * getA(), getB(), getX(), getY() - Yüz butonları + * getLB(), getRB() - Omuz butonları (bumper) + * getStart(), getBack() - Menü butonları + * + * D-PAD (int, derece cinsinden): + * getPOV() - Yön: 0=yukarı, 90=sağ, 180=aşağı, 270=sol, -1=basılı değil + * + * SEQUENCE NUMARASI: + * getSeq() - Her yeni veri paketinde artar. Verinin güncel olup + * olmadığını kontrol etmek için kullanılır. + * + * ============================================================================ + * İPUÇLARI + * ============================================================================ + * - Stick dead zone: Joystick ortada bile tam 0.0 vermeyebilir. + * Genelde |değer| < 0.1 ise 0 kabul edilir. + * + * - Veri güncelliği: getSeq() değeri değişmiyorsa DriverStation bağlı + * olmayabilir veya veri göndermiyor olabilir. + * + * - Teleop modu: Joystick verisi sadece teleop modunda aktif olarak + * güncellenir. Otonom modda joystick okunmaz. + * + * ============================================================================ + */ + +#define PROBOT_WIFI_AP_PASSWORD "ProBot1234" + #include #include -#include -#include -#include - -// Pin atamalarını kendi kartınıza göre güncelleyin. -static constexpr int PIN_INA = 47; -static constexpr int PIN_INB = 46; -static constexpr int PIN_PWM = 48; -static constexpr int PIN_ENA = -1; // EN pinleri 3V3'e bağlıysa -1 bırakmak yeterli. -static constexpr int PIN_ENB = -1; - -// Tüm örneklerde aynı temel motor-stub setini kullanıyoruz. -static probot::motor::BoardozaVNHMotorDriver motor(PIN_INA, PIN_INB, PIN_PWM, PIN_ENA, PIN_ENB); -static probot::sensors::NullEncoder encoder; -static const probot::control::PidConfig kPid{.kp = 0.25f, .ki = 0.0f, .kd = 0.0f, .kf = 0.0f, - .out_min = -1.0f, .out_max = 1.0f}; -static probot::control::PID pid(kPid); -static probot::control::ClosedLoopMotor controller(&encoder, &pid, &motor, 1.0f, 1.0f); - -PROBOT_SET_DRIVER_STATION_PASSWORD("ProBot1234"); +/** + * Robot başlatıldığında çağrılır (bir kez) + */ void robotInit() { Serial.begin(115200); delay(100); - // Kart ve sürücüyü hazırla. - motor.begin(); - motor.setBrakeMode(true); // boşta tam fren uygula - controller.setSetpoint(0.0f, probot::control::ControlType::kPercent); - - Serial.println("[JoystickTest] robotInit: Joystick ve motor izleme başlatıldı"); + Serial.println("============================================"); + Serial.println("[JoystickTest] Joystick veri okuma örneği"); + Serial.println("============================================"); + Serial.println("DriverStation'dan bağlanın ve joystick kullanın."); + Serial.println(""); + Serial.println("Veri formatı:"); + Serial.println(" seq = Paket sıra numarası"); + Serial.println(" LX/LY = Sol stick X/Y ekseni"); + Serial.println(" RX/RY = Sağ stick X/Y ekseni"); + Serial.println(" A/B/X/Y = Yüz butonları (0 veya 1)"); } +/** + * Robot durdurulduğunda çağrılır + */ void robotEnd() { - controller.setPowerDirect(0.0f); // çıkışları güvenle sıfırla - Serial.println("[JoystickTest] robotEnd: Motor sıfırlandı"); + Serial.println("[JoystickTest] Bitti"); } +/** + * Teleop modu başladığında çağrılır + */ void teleopInit() { - Serial.println("[JoystickTest] teleopInit: Ekseni okuyup motora aktaracağız"); + Serial.println("[JoystickTest] Teleop başladı - joystick verilerini izleyin"); + Serial.println(""); } +/** + * Teleop döngüsü (sürekli çağrılır) + * + * Bu fonksiyon joystick verilerini okur ve hem seri porta hem de + * telemetri sistemine yazdırır. DriverStation'da telemetri panelinde + * bu veriler görünür. + */ void teleopLoop() { + // Joystick API'sinden veri al + // makeDefault() her çağrıda en güncel veriyi döner auto js = probot::io::joystick_api::makeDefault(); - // Sol çubuk Y eksenini oku (varsayılan eşleme). - float axis = js.getLeftY(); + // ========================================================================= + // SERİ PORT ÇIKTISI + // ========================================================================= + // Seri monitörde görünür (USB üzerinden) + Serial.printf("seq=%lu | LX=%.2f LY=%.2f | RX=%.2f RY=%.2f | LT=%.2f RT=%.2f\n", + static_cast(js.getSeq()), + js.getLeftX(), js.getLeftY(), + js.getRightX(), js.getRightY(), + js.getLeftTriggerAxis(), js.getRightTriggerAxis()); + + Serial.printf(" | A=%d B=%d X=%d Y=%d | LB=%d RB=%d | POV=%d\n", + js.getA(), js.getB(), js.getX(), js.getY(), + js.getLB(), js.getRB(), + js.getPOV()); - // Okuduğumuz değeri doğrudan motora gönderiyoruz. - controller.setPowerDirect(axis); + // ========================================================================= + // TELEMETRİ ÇIKTISI + // ========================================================================= + // DriverStation uygulamasında telemetri panelinde görünür. + // HTTP polling ile 50ms'de bir güncellenir. + // + // API: + // clear() - Buffer'ı temizle (her döngü başında çağır) + // print() - String yaz + // println() - String yaz + yeni satır + // printf() - Formatlanmış çıktı - // Seri log ile joystick verisini ve motor komutunu gözlemleyin. - Serial.printf("[JoystickTest] seq=%lu axisY=%.2f motorCmd=%.2f\n", - static_cast(js.getSeq()), - axis, - controller.lastOutput()); + // Her döngüde buffer'ı temizle, yoksa veriler birikir + probot::telemetry::clear(); + + // Başlık + probot::telemetry::println("=== JOYSTICK TEST ==="); + + // Sol stick + probot::telemetry::printf("Sol Stick: X=%.2f Y=%.2f\n", + js.getLeftX(), js.getLeftY()); - delay(50); + // Sağ stick + probot::telemetry::printf("Sag Stick: X=%.2f Y=%.2f\n", + js.getRightX(), js.getRightY()); + + // Tetikler + probot::telemetry::printf("Tetikler: LT=%.2f RT=%.2f\n", + js.getLeftTriggerAxis(), js.getRightTriggerAxis()); + + // Butonlar - basılı olanları göster + probot::telemetry::print("Butonlar: "); + if (js.getA()) probot::telemetry::print("A "); + if (js.getB()) probot::telemetry::print("B "); + if (js.getX()) probot::telemetry::print("X "); + if (js.getY()) probot::telemetry::print("Y "); + if (js.getLB()) probot::telemetry::print("LB "); + if (js.getRB()) probot::telemetry::print("RB "); + if (js.getStart()) probot::telemetry::print("START "); + if (js.getBack()) probot::telemetry::print("BACK "); + probot::telemetry::println(""); + + // D-Pad (POV) + int pov = js.getPOV(); + probot::telemetry::print("D-Pad: "); + if (pov == -1) { + probot::telemetry::println("-"); + } else if (pov == 0) { + probot::telemetry::println("YUKARI"); + } else if (pov == 90) { + probot::telemetry::println("SAG"); + } else if (pov == 180) { + probot::telemetry::println("ASAGI"); + } else if (pov == 270) { + probot::telemetry::println("SOL"); + } else { + probot::telemetry::printf("%d derece\n", pov); + } + + // Sequence numarası + probot::telemetry::printf("Seq: %lu\n", static_cast(js.getSeq())); + + // 10 Hz güncelleme (100ms) + delay(100); } +/** + * Otonom modu başladığında çağrılır + */ void autonomousInit() { - Serial.println("[JoystickTest] autonomousInit: Bu örnek otonomda motoru durdurur"); - controller.setPowerDirect(0.0f); + Serial.println("[JoystickTest] Otonom - joystick okumuyor"); } +/** + * Otonom döngüsü + * + * Bu örnekte otonom modda bir şey yapılmıyor. + * Joystick verisi otonom modda güncellenmez. + */ void autonomousLoop() { - // Joystick okumadığımız için otonomda motoru sıfırda tutuyoruz. - controller.update(millis(), 20); - delay(20); + delay(100); } diff --git a/examples/LoggingDemo/LoggingDemo.ino b/examples/LoggingDemo/LoggingDemo.ino deleted file mode 100644 index 99d0e2e..0000000 --- a/examples/LoggingDemo/LoggingDemo.ino +++ /dev/null @@ -1,111 +0,0 @@ -/** - * LoggingDemo.ino - * - * Quick check for the serial/Wi-Fi logging stack. Registers a demo source, - * pushes a heartbeat counter every 500 ms, and exposes a static snapshot. Use - * the driver station UI (minimal stack) to see Wi-Fi log streaming, or watch - * the binary frames on the serial monitor. - */ - -#include -#include - -namespace { - -struct DemoSource { - const probot::logging::SourceRegistration* reg{nullptr}; - uint32_t boot_ms{0}; - uint32_t counter{0}; -} demo; - -void demoStaticInfo(const void* object, - probot::logging::TelemetryCollector& collector) { - auto src = static_cast(object); - collector.addInt("boot_ms", src->boot_ms, probot::logging::Priority::kSystemCritical); - collector.addString("note", "Demo static snapshot", probot::logging::Priority::kUserMarked); -} - -void publishCounter(uint32_t now_ms) { - if (!demo.reg) return; - demo.counter++; - auto& mgr = probot::logging::manager(); - mgr.enqueueValue(*demo.reg, - &demo, - "counter", - probot::logging::ValueType::kInt, - probot::logging::Priority::kUserMarked, - static_cast(demo.counter), - 0.0f, - false, - nullptr, - now_ms); - mgr.enqueueValue(*demo.reg, - &demo, - "uptime_ms", - probot::logging::ValueType::kInt, - probot::logging::Priority::kBackground, - static_cast(now_ms), - 0.0f, - false, - nullptr, - now_ms); -} - -} // namespace - -static uint32_t last_publish_ms = 0; - -void robotInit(){ - Serial.begin(115200); - delay(200); - - probot::logging::configureDefaults(); - probot::logging::enableSerialLogging(true); - probot::logging::setSerialBandwidthMode(probot::logging::BandwidthMode::kNormal); - probot::logging::enableWifiLogging(true); - probot::logging::setWifiStreamingEnabled(true); - - demo.boot_ms = millis(); - - probot::logging::SourceRegistration reg{ - "demo", - "logging", - probot::logging::Priority::kUserMarked, - true, - true, - nullptr, - demoStaticInfo - }; - demo.reg = probot::logging::registerSource(&demo, reg); - - Serial.println(); - Serial.println(F("[LoggingDemo] Logging configured. Check the driver UI")); -} - -void robotEnd(){ - if (demo.reg){ - probot::logging::unregisterSource(&demo); - demo.reg = nullptr; - } -} - -void teleopInit(){ - last_publish_ms = millis(); -} - -void teleopLoop(){ - uint32_t now = millis(); - if (now - last_publish_ms >= 500){ - publishCounter(now); - last_publish_ms = now; - } - vTaskDelay(pdMS_TO_TICKS(5)); -} - -void autonomousInit(){ - teleopInit(); -} - -void autonomousLoop(){ - teleopLoop(); -} diff --git a/examples/MecanumDriveDemo/MecanumDriveDemo.ino b/examples/MecanumDriveDemo/MecanumDriveDemo.ino deleted file mode 100644 index d38ce88..0000000 --- a/examples/MecanumDriveDemo/MecanumDriveDemo.ino +++ /dev/null @@ -1,110 +0,0 @@ -#include -#include -#include -#include -#include -#include - -// Mecanum sürüş için dört motorun pin atamaları. -struct MotorPins { - int ina, inb, pwm, ena, enb; -}; - -static constexpr MotorPins PINS_FL{18, 19, 20, -1, -1}; -static constexpr MotorPins PINS_FR{21, 22, 23, -1, -1}; -static constexpr MotorPins PINS_RL{24, 25, 26, -1, -1}; -static constexpr MotorPins PINS_RR{27, 28, 29, -1, -1}; - -static probot::motor::BoardozaVNHMotorDriver drvFL(PINS_FL.ina, PINS_FL.inb, PINS_FL.pwm, PINS_FL.ena, PINS_FL.enb); -static probot::motor::BoardozaVNHMotorDriver drvFR(PINS_FR.ina, PINS_FR.inb, PINS_FR.pwm, PINS_FR.ena, PINS_FR.enb); -static probot::motor::BoardozaVNHMotorDriver drvRL(PINS_RL.ina, PINS_RL.inb, PINS_RL.pwm, PINS_RL.ena, PINS_RL.enb); -static probot::motor::BoardozaVNHMotorDriver drvRR(PINS_RR.ina, PINS_RR.inb, PINS_RR.pwm, PINS_RR.ena, PINS_RR.enb); - -static probot::sensors::NullEncoder encFL; -static probot::sensors::NullEncoder encFR; -static probot::sensors::NullEncoder encRL; -static probot::sensors::NullEncoder encRR; - -static const probot::control::PidConfig kPid{.kp = 0.30f, .ki = 0.01f, .kd = 0.0f, .kf = 0.0f, - .out_min = -1.0f, .out_max = 1.0f}; - -static probot::control::PID pidFL(kPid); -static probot::control::PID pidFR(kPid); -static probot::control::PID pidRL(kPid); -static probot::control::PID pidRR(kPid); - -static probot::control::ClosedLoopMotor motorFL(&encFL, &pidFL, &drvFL, 1.0f, 1.0f); -static probot::control::ClosedLoopMotor motorFR(&encFR, &pidFR, &drvFR, 1.0f, 1.0f); -static probot::control::ClosedLoopMotor motorRL(&encRL, &pidRL, &drvRL, 1.0f, 1.0f); -static probot::control::ClosedLoopMotor motorRR(&encRR, &pidRR, &drvRR, 1.0f, 1.0f); - -static probot::chassis::SimpleMecanumDrive mecanum(&motorFL, &motorFR, &motorRL, &motorRR); - -PROBOT_SET_DRIVER_STATION_PASSWORD("ProBot1234"); - -void robotInit() { - Serial.begin(115200); - delay(100); - - drvFL.begin(); drvFR.begin(); drvRL.begin(); drvRR.begin(); - drvFL.setBrakeMode(true); - drvFR.setBrakeMode(true); - drvRL.setBrakeMode(true); - drvRR.setBrakeMode(true); - - mecanum.setInverted(false, true, false, true); // sağ taraf ters kabloluysa düzelt - - Serial.println("[MecanumDriveDemo] robotInit: Mecanum sürüşe hazır"); -} - -void robotEnd() { - mecanum.stop(); - Serial.println("[MecanumDriveDemo] robotEnd: Motorlar kapatıldı"); -} - -void teleopInit() { - Serial.println("[MecanumDriveDemo] teleopInit:" - " sol çubuk Y ileri-geri, X yan, sağ X dönüş"); -} - -void teleopLoop() { - auto js = probot::io::joystick_api::makeDefault(); - - float vx = js.getLeftY(); // ileri geri - float vy = js.getLeftX(); // yan hareket - float omega = js.getRightX();// dönüş - - mecanum.driveCartesian(vx, vy, omega); - - Serial.printf("[MecanumDriveDemo] vx=%.2f vy=%.2f w=%.2f fl=%.2f fr=%.2f rl=%.2f rr=%.2f\n", - vx, vy, omega, - motorFL.lastOutput(), motorFR.lastOutput(), - motorRL.lastOutput(), motorRR.lastOutput()); - - delay(20); -} - -void autonomousInit() { - Serial.println("[MecanumDriveDemo] autonomousInit: kare rota denemesi"); -} - -void autonomousLoop() { - static uint32_t start = millis(); - uint32_t elapsed = millis() - start; - float vx = 0.0f, vy = 0.0f, omega = 0.0f; - - if (elapsed < 2000) { - vx = 0.6f; // ileri - } else if (elapsed < 4000) { - vy = 0.6f; // sağa kay - } else if (elapsed < 6000) { - vx = -0.6f; // geri - } else if (elapsed < 8000) { - vy = -0.6f; // sola kay - } else { - start = millis(); - } - - mecanum.driveCartesian(vx, vy, omega); - delay(20); -} diff --git a/examples/MotorControllerDemo/MotorControllerDemo.ino b/examples/MotorControllerDemo/MotorControllerDemo.ino deleted file mode 100644 index e975818..0000000 --- a/examples/MotorControllerDemo/MotorControllerDemo.ino +++ /dev/null @@ -1,87 +0,0 @@ -#include -#include -#include -#include -#include - -// Kullanılan Boardoza VNH sürücü pinleri (kendi kartınıza göre güncelleyin). -static constexpr int PIN_INA = 9; -static constexpr int PIN_INB = 10; -static constexpr int PIN_PWM = 11; -static constexpr int PIN_ENA = -1; -static constexpr int PIN_ENB = -1; - -static probot::motor::BoardozaVNHMotorDriver motor(PIN_INA, PIN_INB, PIN_PWM, PIN_ENA, PIN_ENB); -static probot::sensors::NullEncoder encoder; -static const probot::control::PidConfig kVelocityPid{.kp = 0.35f, .ki = 0.02f, .kd = 0.0f, - .kf = 0.0f, .out_min = -1.0f, .out_max = 1.0f}; -static probot::control::PID pid(kVelocityPid); -static probot::control::ClosedLoopMotor controller(&encoder, &pid, &motor, 1.0f, 1.0f); - -PROBOT_SET_DRIVER_STATION_PASSWORD("ProBot1234"); - -static probot::control::ControlType g_mode = probot::control::ControlType::kVelocity; - -void robotInit() { - Serial.begin(115200); - delay(100); - - motor.begin(); - motor.setBrakeMode(true); - - controller.setTimeoutMs(0); // joystick bırakıldığında çıkış sıfırlanmasın - controller.setSetpoint(0.0f, g_mode); - - Serial.println("[MotorControllerDemo] robotInit: Kapalı çevrim denemesi için hazır"); -} - -void robotEnd() { - controller.setPowerDirect(0.0f); - Serial.println("[MotorControllerDemo] robotEnd: Motor kapatıldı"); -} - -void teleopInit() { - Serial.println("[MotorControllerDemo] teleopInit:" - " sol eksen referans, A butonu mod değiştirir (yüzde/velocity)"); -} - -void teleopLoop() { - auto js = probot::io::joystick_api::makeDefault(); - - if (js.getRawButton(0)) { - g_mode = (g_mode == probot::control::ControlType::kVelocity) - ? probot::control::ControlType::kPercent - : probot::control::ControlType::kVelocity; - controller.setSetpoint(0.0f, g_mode); - Serial.printf("[MotorControllerDemo] Mod değişti: %s\n", - g_mode == probot::control::ControlType::kVelocity ? "HIZ" : "YÜZDE"); - delay(200); // buton debouncing - } - - float axis = js.getLeftY(); - float target = axis * (g_mode == probot::control::ControlType::kVelocity ? 100.0f : 1.0f); - controller.setSetpoint(target, g_mode); - controller.update(millis(), 20); - - Serial.printf("[MotorControllerDemo] mode=%s target=%.2f measurement=%.2f out=%.2f\n", - g_mode == probot::control::ControlType::kVelocity ? "VEL" : "PCT", - target, - controller.lastMeasurement(), - controller.lastOutput()); - - delay(20); -} - -void autonomousInit() { - Serial.println("[MotorControllerDemo] autonomousInit: 2 saniyelik hız profili"); - controller.setSetpoint(80.0f, probot::control::ControlType::kVelocity); -} - -void autonomousLoop() { - static uint32_t start = millis(); - controller.update(millis(), 20); - if (millis() - start > 2000) { - controller.setSetpoint(0.0f, probot::control::ControlType::kVelocity); - } - delay(20); -} diff --git a/examples/MotorDriverDemo/MotorDriverDemo.ino b/examples/MotorDriverDemo/MotorDriverDemo.ino deleted file mode 100644 index 625166e..0000000 --- a/examples/MotorDriverDemo/MotorDriverDemo.ino +++ /dev/null @@ -1,71 +0,0 @@ -#include -#include -#include -#include -#include - -// Boardoza VNH sürücüsünü kullanırken kendi pinlerinizi mutlaka kontrol edin. -static constexpr int PIN_INA = 39; -static constexpr int PIN_INB = 40; -static constexpr int PIN_PWM = 41; -static constexpr int PIN_ENA = -1; -static constexpr int PIN_ENB = -1; - -static probot::motor::BoardozaVNHMotorDriver motor(PIN_INA, PIN_INB, PIN_PWM, PIN_ENA, PIN_ENB); -static probot::sensors::NullEncoder encoder; -static const probot::control::PidConfig kPid{.kp = 0.30f, .ki = 0.0f, .kd = 0.0f, .kf = 0.0f, - .out_min = -1.0f, .out_max = 1.0f}; -static probot::control::PID pid(kPid); -static probot::control::ClosedLoopMotor controller(&encoder, &pid, &motor, 1.0f, 1.0f); - -PROBOT_SET_DRIVER_STATION_PASSWORD("ProBot1234"); - -void robotInit() { - Serial.begin(115200); - delay(100); - - motor.begin(); - motor.setBrakeMode(false); // sürücü serbest bırakıldı, coast modunda - controller.setInverted(false); - - Serial.println("[MotorDriverDemo] robotInit: IMotorDriver arayüzünü test etmek için hazır"); -} - -void robotEnd() { - motor.setPower(0.0f); - Serial.println("[MotorDriverDemo] robotEnd: Motor durduruldu"); -} - -void teleopInit() { - Serial.println("[MotorDriverDemo] teleopInit:" - " sol eksen gücü, sağ tetik ise yön tersleme yapar"); -} - -void teleopLoop() { - auto js = probot::io::joystick_api::makeDefault(); - - // Sol çubuktan ham güç, sağ tetikten tersleme isteği okuyoruz. - float power = js.getLeftY(); - bool invert = js.getRightTriggerAxis() > 0.5f; - - motor.setInverted(invert); - - // IMotorDriver doğrudan PWM uygular; ClosedLoopMotor'u sadece izleme için kullanıyoruz. - motor.setPower(power); - controller.setPowerDirect(power); // lastOutput() bilgisi için eşleştiriyoruz. - - Serial.printf("[MotorDriverDemo] power=%.2f invert=%d motorOut=%.2f\n", - power, invert ? 1 : 0, controller.lastOutput()); - - delay(40); -} - -void autonomousInit() { - Serial.println("[MotorDriverDemo] autonomousInit: Motoru yavaşça durduruyoruz"); -} - -void autonomousLoop() { - motor.setPower(0.0f); - controller.update(millis(), 20); - delay(20); -} diff --git a/examples/MotorOpenLoopDemo/MotorOpenLoopDemo.ino b/examples/MotorOpenLoopDemo/MotorOpenLoopDemo.ino new file mode 100644 index 0000000..7af948a --- /dev/null +++ b/examples/MotorOpenLoopDemo/MotorOpenLoopDemo.ino @@ -0,0 +1,151 @@ +/** + * MotorOpenLoopDemo - Açık çevrim motor kontrol örneği + * + * Bu örnek probot'un motor driver soyutlamasını kullanarak + * tek bir motoru joystick ile kontrol eder. + * + * ============================================================================ + * NE ÖĞRENECEKSINIZ? + * ============================================================================ + * - IMotorController arayüzünün kullanımı + * - BoardozaVNH5019MotorController driver'ının kurulumu + * - Joystick'ten motor gücü okuma + * - Motor yön terslemesi (invert) + * - Açık çevrim (open-loop) kontrol mantığı + * + * ============================================================================ + * AÇIK ÇEVRİM vs KAPALI ÇEVRİM + * ============================================================================ + * Açık çevrim: Motora güç gönderirsin, ne olduğunu kontrol etmezsin. + * Encoder yok, PID yok. Basit ama hassas değil. + * + * Kapalı çevrim: Encoder ile hızı ölçersin, PID ile düzeltirsin. + * Daha karmaşık ama hassas kontrol sağlar. + * + * Bu örnek AÇIK ÇEVRİM kullanır - encoder gerektirmez. + * + * ============================================================================ + * DONANIM BAĞLANTISI + * ============================================================================ + * Boardoza VNH5019 motor driver kullanılıyor: + * + * VNH5019 Pin | ESP32 Pin | Açıklama + * -------------|-------------|---------------------------------- + * INA | GPIO 39 | Yön kontrolü A + * INB | GPIO 40 | Yön kontrolü B + * PWM | GPIO 41 | Hız kontrolü (PWM) + * ENA/ENB | -1 (yok) | Enable pinleri (3.3V'a bağlı) + * + * Pin numaralarını kendi kartınıza göre değiştirin! + * + * ============================================================================ + * KONTROLLER + * ============================================================================ + * - Sol stick Y ekseni: Motor gücü (-1.0 ile 1.0 arası) + * - Sağ tetik: Basılıyken motor yönünü tersler + * + * ============================================================================ + */ + +#define PROBOT_WIFI_AP_PASSWORD "ProBot1234" + +#include +#include +#include + +// ============================================================================ +// PIN AYARLARI - Kendi kartınıza göre değiştirin! +// ============================================================================ +static constexpr int PIN_INA = 39; // Yön A pini +static constexpr int PIN_INB = 40; // Yön B pini +static constexpr int PIN_PWM = 41; // PWM pini +static constexpr int PIN_ENA = -1; // Enable A (-1 = kullanılmıyor) +static constexpr int PIN_ENB = -1; // Enable B (-1 = kullanılmıyor) + +// Motor controller nesnesi +// Bu sınıf IMotorController arayüzünü uygular +static probot::motor::BoardozaVNH5019MotorController motor(PIN_INA, PIN_INB, PIN_PWM, PIN_ENA, PIN_ENB); + +/** + * Robot başlatıldığında çağrılır (bir kez) + */ +void robotInit() { + Serial.begin(115200); + delay(100); + + // Motor driver'ı başlat + // Bu fonksiyon pin modlarını ayarlar ve PWM'i yapılandırır + motor.begin(); + + // Fren modu: false = coast (serbest), true = brake (fren) + // Coast modunda motor serbest döner, brake modunda dirençle durur + motor.setBrakeMode(false); + + // Yön terslemesi: false = normal, true = ters + motor.setInverted(false); + + Serial.println("[MotorOpenLoopDemo] Motor driver hazır"); + Serial.println(" Sol stick Y: Motor gücü"); + Serial.println(" Sağ tetik: Yön tersle"); +} + +/** + * Robot durdurulduğunda çağrılır + */ +void robotEnd() { + // Güvenlik: Motoru durdur + motor.setPower(0.0f); + Serial.println("[MotorOpenLoopDemo] Motor durduruldu"); +} + +/** + * Teleop modu başladığında çağrılır + */ +void teleopInit() { + Serial.println("[MotorOpenLoopDemo] Teleop başladı"); +} + +/** + * Teleop döngüsü (sürekli çağrılır) + */ +void teleopLoop() { + // Joystick verilerini al + auto js = probot::io::joystick_api::makeDefault(); + + // Sol stick Y ekseninden motor gücü oku + // Değer -1.0 (tam geri) ile 1.0 (tam ileri) arasında + float power = js.getLeftY(); + + // Sağ tetik basılıysa yönü tersle + bool invert = js.getRightTriggerAxis() > 0.5f; + motor.setInverted(invert); + + // Motora güç gönder + // setPower() değeri -1.0 ile 1.0 arasında alır + motor.setPower(power); + + // Debug çıktısı + Serial.printf("[Motor] güç=%.2f ters=%d çıkış=%.2f\n", + power, invert ? 1 : 0, motor.getPower()); + + // Telemetri (DriverStation'da görünür) + probot::telemetry::printf("Motor: %.2f\n", motor.getPower()); + + delay(40); // 25 Hz güncelleme +} + +/** + * Otonom modu başladığında çağrılır + */ +void autonomousInit() { + Serial.println("[MotorOpenLoopDemo] Otonom başladı - motor duracak"); +} + +/** + * Otonom döngüsü + */ +void autonomousLoop() { + // Otonomda motoru durdur (joystick yok) + motor.setPower(0.0f); + delay(20); +} diff --git a/examples/ShooterDemo/ShooterDemo.ino b/examples/ShooterDemo/ShooterDemo.ino deleted file mode 100644 index 7a69c92..0000000 --- a/examples/ShooterDemo/ShooterDemo.ino +++ /dev/null @@ -1,83 +0,0 @@ -#include -#include -#include -#include -#include -#include - -// Shooter tekeri için Boardoza VNH pin konfigürasyonu. -static constexpr int PIN_INA = 15; -static constexpr int PIN_INB = 16; -static constexpr int PIN_PWM = 17; -static constexpr int PIN_ENA = -1; -static constexpr int PIN_ENB = -1; - -static probot::motor::BoardozaVNHMotorDriver motor(PIN_INA, PIN_INB, PIN_PWM, PIN_ENA, PIN_ENB); -static probot::sensors::NullEncoder encoder; -static const probot::control::PidConfig kVelocityPid{.kp = 0.4f, .ki = 0.02f, .kd = 0.0f, - .kf = 0.0f, .out_min = -1.0f, .out_max = 1.0f}; -static probot::control::PID pid(kVelocityPid); -static probot::control::ClosedLoopMotor shooterMotor(&encoder, &pid, &motor, 1.0f, 1.0f); -static probot::mechanism::nfr::NfrShooter shooter(&shooterMotor); - -PROBOT_SET_DRIVER_STATION_PASSWORD("ProBot1234"); - -void robotInit() { - Serial.begin(115200); - delay(100); - - motor.begin(); - motor.setBrakeMode(false); // shooter çarkında coast tercihi yapılabilir - - shooterMotor.setTimeoutMs(0); - shooterMotor.selectDefaultSlot(probot::control::ControlType::kVelocity, 0); - shooterMotor.setPidSlotConfig(0, kVelocityPid); - shooter.setTicksPerRevolution(4096.0f); // kullandığınız enkoder değerini girin - shooter.setRpm(0.0f, 0.0f); - - Serial.println("[ShooterDemo] robotInit: Shooter kontrolü başlatıldı"); -} - -void robotEnd() { - shooter.stop(); - Serial.println("[ShooterDemo] robotEnd: Teker kapatıldı"); -} - -void teleopInit() { - Serial.println("[ShooterDemo] teleopInit:" - " sağ tetik hızlandırır, sol tetik fren yapar"); -} - -void teleopLoop() { - auto js = probot::io::joystick_api::makeDefault(); - - float accel = js.getRightTriggerAxis(); // 0..1 - float brake = js.getLeftTriggerAxis(); // 0..1 - - float targetRpm = accel * 3200.0f; // istenen maksimum RPM - if (brake > 0.2f) targetRpm = 0.0f; // fren tetiklendiğinde durdur - - shooter.setPrimaryRpm(targetRpm); - shooterMotor.update(millis(), 20); - - Serial.printf("[ShooterDemo] hedef=%.0f rpm ölçüm=%.1f rpm çıkış=%.2f\n", - targetRpm, - shooterMotor.lastMeasurement(), - shooterMotor.lastOutput()); - - delay(20); -} - -void autonomousInit() { - Serial.println("[ShooterDemo] autonomousInit: 2 saniye spool, sonra durdur"); - shooter.setPrimaryRpm(3000.0f); -} - -void autonomousLoop() { - static uint32_t start = millis(); - shooterMotor.update(millis(), 20); - if (millis() - start > 2000) { - shooter.stop(); - } - delay(20); -} diff --git a/examples/SliderDemo/SliderDemo.ino b/examples/SliderDemo/SliderDemo.ino deleted file mode 100644 index 2263d28..0000000 --- a/examples/SliderDemo/SliderDemo.ino +++ /dev/null @@ -1,97 +0,0 @@ -#include -#include -#include -#include -#include -#include - -// Slider mekanizması için kullanılan VNH sürücü pinleri. -static constexpr int PIN_INA = 12; -static constexpr int PIN_INB = 13; -static constexpr int PIN_PWM = 14; -static constexpr int PIN_ENA = -1; -static constexpr int PIN_ENB = -1; - -static probot::motor::BoardozaVNHMotorDriver motor(PIN_INA, PIN_INB, PIN_PWM, PIN_ENA, PIN_ENB); -static probot::sensors::NullEncoder encoder; -static const probot::control::PidConfig kPositionPid{.kp = 0.5f, .ki = 0.0f, .kd = 0.0f, .kf = 0.0f, - .out_min = -1.0f, .out_max = 1.0f}; -static probot::control::PID pid(kPositionPid); -static probot::control::ClosedLoopMotor controller(&encoder, &pid, &motor, 1.0f, 1.0f); -static probot::mechanism::Slider slider(&controller); - -PROBOT_SET_DRIVER_STATION_PASSWORD("ProBot1234"); - -void robotInit() { - Serial.begin(115200); - delay(100); - - motor.begin(); - motor.setBrakeMode(true); - - controller.selectDefaultSlot(probot::control::ControlType::kPosition, 0); - controller.setPidSlotConfig(0, kPositionPid); - controller.setSetpoint(0.0f, probot::control::ControlType::kPosition); - - slider.setLengthToTicks(200.0f); // 1 cm için 200 encoder tıkı varsayalım - slider.setLengthLimits(0.0f, 50.0f); // 0 - 50 cm arası güvenli bölge - - Serial.println("[SliderDemo] robotInit: Slider kontrolü hazır"); -} - -void robotEnd() { - controller.setPowerDirect(0.0f); - Serial.println("[SliderDemo] robotEnd: Motor sıfırlandı"); -} - -void teleopInit() { - Serial.println("[SliderDemo] teleopInit:" - " D-pad ile 0/15/30/45 cm hedefleri seçilir"); -} - -void teleopLoop() { - auto js = probot::io::joystick_api::makeDefault(); - int pov = js.getPOV(); - - if (pov == 0) slider.setTargetLength(45.0f); // yukarı - if (pov == 90) slider.setTargetLength(30.0f); // sağ - if (pov == 180) slider.setTargetLength(0.0f); // aşağı - if (pov == 270) slider.setTargetLength(15.0f); // sol - - slider.update(millis(), 20); - controller.update(millis(), 20); - - Serial.printf("[SliderDemo] hedef=%.1f cm ölçüm=%.1f cm çıkış=%.2f\n", - slider.getTargetLength(), - slider.getCurrentLength(), - controller.lastOutput()); - - delay(20); -} - -void autonomousInit() { - Serial.println("[SliderDemo] autonomousInit: 3 adımda preset dolaşımı"); -} - -void autonomousLoop() { - static uint32_t stateStart = millis(); - static int state = 0; - uint32_t now = millis(); - - if (state == 0) { - slider.setTargetLength(10.0f); - stateStart = now; - state = 1; - } else if (state == 1 && now - stateStart > 1500) { - slider.setTargetLength(40.0f); - stateStart = now; - state = 2; - } else if (state == 2 && now - stateStart > 1500) { - slider.setTargetLength(0.0f); - state = 3; - } - - slider.update(now, 20); - controller.update(now, 20); - delay(20); -} diff --git a/examples/TankDriveDemo/TankDriveDemo.ino b/examples/TankDriveDemo/TankDriveDemo.ino deleted file mode 100644 index 9225314..0000000 --- a/examples/TankDriveDemo/TankDriveDemo.ino +++ /dev/null @@ -1,118 +0,0 @@ -#include -#include -#include -#include -#include -#include - -// Tank şasi için iki adet VNH sürücünün pin eşlemesi (örnek değerler). -static constexpr int LEFT_INA = 1; -static constexpr int LEFT_INB = 2; -static constexpr int LEFT_PWM = 3; -static constexpr int LEFT_ENA = -1; -static constexpr int LEFT_ENB = -1; - -static constexpr int RIGHT_INA = 4; -static constexpr int RIGHT_INB = 5; -static constexpr int RIGHT_PWM = 6; -static constexpr int RIGHT_ENA = -1; -static constexpr int RIGHT_ENB = -1; - -static probot::motor::BoardozaVNHMotorDriver leftDriver(LEFT_INA, LEFT_INB, LEFT_PWM, LEFT_ENA, LEFT_ENB); -static probot::motor::BoardozaVNHMotorDriver rightDriver(RIGHT_INA, RIGHT_INB, RIGHT_PWM, RIGHT_ENA, RIGHT_ENB); -static probot::sensors::NullEncoder leftEncoder; -static probot::sensors::NullEncoder rightEncoder; - -static const probot::control::PidConfig kPidCfg{.kp = 0.28f, .ki = 0.01f, .kd = 0.0f, .kf = 0.0f, - .out_min = -1.0f, .out_max = 1.0f}; -static probot::control::PID pidLeft(kPidCfg); -static probot::control::PID pidRight(kPidCfg); -static probot::control::ClosedLoopMotor motorLeft(&leftEncoder, &pidLeft, &leftDriver, 1.0f, 1.0f); -static probot::control::ClosedLoopMotor motorRight(&rightEncoder, &pidRight, &rightDriver, 1.0f, 1.0f); -static probot::drive::BasicTankDrive chassis(&motorLeft, &motorRight); - -PROBOT_SET_DRIVER_STATION_PASSWORD("ProBot1234"); - -void robotInit() { - Serial.begin(115200); - delay(100); - - leftDriver.begin(); - rightDriver.begin(); - leftDriver.setBrakeMode(true); - rightDriver.setBrakeMode(true); - - motorLeft.setTimeoutMs(0); - motorRight.setTimeoutMs(0); - - chassis.setWheelCircumference(31.4f); // örnek teker çapı ayarı - chassis.setTrackWidth(28.0f); // örnek şasi genişliği - - Serial.println("[TankDriveDemo] robotInit: Tank şasi hazır"); -} - -void robotEnd() { - chassis.setVelocity(0.0f, 0.0f); - motorLeft.setPowerDirect(0.0f); - motorRight.setPowerDirect(0.0f); - Serial.println("[TankDriveDemo] robotEnd: Motorlar kapandı"); -} - -void teleopInit() { - Serial.println("[TankDriveDemo] teleopInit: Sol/Sağ joystick ile tank sürüşü"); -} - -void teleopLoop() { - auto js = probot::io::joystick_api::makeDefault(); - - float leftCmd = js.getLeftY() * 120.0f; // cm/s cinsinden hedef hız - float rightCmd = js.getRightY() * 120.0f; - - chassis.setVelocity(leftCmd, rightCmd); - - uint32_t now = millis(); - chassis.update(now, 20); - - Serial.printf("[TankDriveDemo] left=%.1f right=%.1f outL=%.2f outR=%.2f\n", - leftCmd, rightCmd, - motorLeft.lastOutput(), motorRight.lastOutput()); - - delay(20); -} - -void autonomousInit() { - Serial.println("[TankDriveDemo] autonomousInit: 3 adımda ilerleme testi"); -} - -void autonomousLoop() { - static uint32_t stateStart = millis(); - static int state = 0; - - uint32_t now = millis(); - switch (state) { - case 0: // 1 metre ileri - chassis.driveDistance(100.0f); - stateStart = now; - state = 1; - break; - case 1: - if (now - stateStart > 3000) { - chassis.turnDegrees(90.0f); - stateStart = now; - state = 2; - } - break; - case 2: - if (now - stateStart > 2500) { - chassis.driveDistance(50.0f); - state = 3; - } - break; - default: - chassis.setVelocity(0.0f, 0.0f); - break; - } - - chassis.update(now, 20); - delay(20); -} diff --git a/examples/TurretDemo/TurretDemo.ino b/examples/TurretDemo/TurretDemo.ino deleted file mode 100644 index 25e248f..0000000 --- a/examples/TurretDemo/TurretDemo.ino +++ /dev/null @@ -1,100 +0,0 @@ -#include -#include -#include -#include -#include -#include - -// Taret döndürme motoru için Boardoza VNH pinleri. -static constexpr int PIN_INA = 30; -static constexpr int PIN_INB = 31; -static constexpr int PIN_PWM = 32; -static constexpr int PIN_ENA = -1; -static constexpr int PIN_ENB = -1; - -static probot::motor::BoardozaVNHMotorDriver motor(PIN_INA, PIN_INB, PIN_PWM, PIN_ENA, PIN_ENB); -static probot::sensors::NullEncoder encoder; -static const probot::control::PidConfig kPositionPid{.kp = 0.6f, .ki = 0.0f, .kd = 0.0f, - .kf = 0.0f, .out_min = -1.0f, .out_max = 1.0f}; -static probot::control::PID pid(kPositionPid); -static probot::control::ClosedLoopMotor turretMotor(&encoder, &pid, &motor, 1.0f, 1.0f); -static probot::mechanism::Turret turret(&turretMotor); - -PROBOT_SET_DRIVER_STATION_PASSWORD("ProBot1234"); - -void robotInit() { - Serial.begin(115200); - delay(100); - - motor.begin(); - motor.setBrakeMode(true); - - turretMotor.selectDefaultSlot(probot::control::ControlType::kPosition, 0); - turretMotor.setPidSlotConfig(0, kPositionPid); - turretMotor.setTimeoutMs(0); - - turret.setDegreesToTicks(100.0f); // encoder dönüşümünü kendi mekanizmanıza göre ayarlayın - turret.setAngleLimits(-120.0f, 120.0f); // güvenli dönüş aralığı - turret.setTargetAngleDeg(0.0f); - turret.setSlewRateLimit(150.0f); // hızlı bile olsa yumuşatma olsun - - Serial.println("[TurretDemo] robotInit: Taret kontrolü hazır"); -} - -void robotEnd() { - turretMotor.setPowerDirect(0.0f); - Serial.println("[TurretDemo] robotEnd: Taret durduruldu"); -} - -void teleopInit() { - Serial.println("[TurretDemo] teleopInit:" - " sağ çubuk X hedef açıyı belirler, B butonu sıfırlar"); -} - -void teleopLoop() { - auto js = probot::io::joystick_api::makeDefault(); - - if (js.getRawButton(1)) { // B butonu - turret.setTargetAngleDeg(0.0f); - } else { - float stick = js.getRightX(); // -1..1 - turret.setTargetAngleDeg(stick * 90.0f); // ±90 derece - } - - turret.update(millis(), 20); - turretMotor.update(millis(), 20); - - Serial.printf("[TurretDemo] hedef=%.1f ölçüm=%.1f çıkış=%.2f\n", - turret.getTargetAngleDeg(), - turret.getCurrentAngleDeg(), - turretMotor.lastOutput()); - - delay(20); -} - -void autonomousInit() { - Serial.println("[TurretDemo] autonomousInit: Rastgele preset taraması"); -} - -void autonomousLoop() { - static uint32_t stateStart = millis(); - static int state = 0; - uint32_t now = millis(); - - if (state == 0) { - turret.setTargetAngleDeg(-60.0f); - stateStart = now; - state = 1; - } else if (state == 1 && now - stateStart > 1500) { - turret.setTargetAngleDeg(60.0f); - stateStart = now; - state = 2; - } else if (state == 2 && now - stateStart > 1500) { - turret.setTargetAngleDeg(0.0f); - state = 3; - } - - turret.update(now, 20); - turretMotor.update(now, 20); - delay(20); -} diff --git a/examples/command_based/AutonomousDemo/AutonomousDemo.ino b/examples/command_based/AutonomousDemo/AutonomousDemo.ino new file mode 100644 index 0000000..9cfb1e4 --- /dev/null +++ b/examples/command_based/AutonomousDemo/AutonomousDemo.ino @@ -0,0 +1,163 @@ +#define PROBOT_WIFI_AP_PASSWORD "ProBot1234" + +#include +#include +#include // Includes scheduler, command, subsystem, command_group +#include +#include + +// Otonom tank demo icin iki adet VNH motor kontrolcusu. +static constexpr int L_INA = 33; +static constexpr int L_INB = 34; +static constexpr int L_PWM = 35; +static constexpr int L_ENA = -1; +static constexpr int L_ENB = -1; + +static constexpr int R_INA = 36; +static constexpr int R_INB = 37; +static constexpr int R_PWM = 38; +static constexpr int R_ENA = -1; +static constexpr int R_ENB = -1; + +static probot::motor::BoardozaVNH5019MotorController leftMotor(L_INA, L_INB, L_PWM, L_ENA, L_ENB); +static probot::motor::BoardozaVNH5019MotorController rightMotor(R_INA, R_INB, R_PWM, R_ENA, R_ENB); +static probot::command::examples::TankDrive chassis(&leftMotor, &rightMotor); + +using Scheduler = probot::command::Scheduler; +using namespace probot::command; + +// ============================================================================ +// Ornek Command'lar - WPILib tarzi command-based otonom +// ============================================================================ + +// Belirli sure ileri git +class DriveForwardCmd : public CommandBase { +public: + DriveForwardCmd(probot::command::examples::TankDrive* drive, float power, uint32_t duration_ms) + : CommandBase("DriveForward"), drive_(drive), power_(power), duration_ms_(duration_ms) { + addRequirement(drive); + } + + void initialize() override { + start_time_ = millis(); + Serial.printf("[Cmd] DriveForward basladi (%.2f, %lums)\n", power_, (unsigned long)duration_ms_); + } + + void execute(uint32_t, uint32_t) override { + drive_->drivePower(power_, power_); + } + + void end(bool interrupted) override { + drive_->stop(); + Serial.printf("[Cmd] DriveForward bitti (interrupted=%d)\n", interrupted); + } + + bool isFinished() const override { + return (millis() - start_time_) >= duration_ms_; + } + +private: + probot::command::examples::TankDrive* drive_; + float power_; + uint32_t duration_ms_; + uint32_t start_time_ = 0; +}; + +// Belirli sure don +class TurnCmd : public CommandBase { +public: + TurnCmd(probot::command::examples::TankDrive* drive, float power, uint32_t duration_ms) + : CommandBase("Turn"), drive_(drive), power_(power), duration_ms_(duration_ms) { + addRequirement(drive); + } + + void initialize() override { + start_time_ = millis(); + Serial.printf("[Cmd] Turn basladi (%.2f, %lums)\n", power_, (unsigned long)duration_ms_); + } + + void execute(uint32_t, uint32_t) override { + drive_->drivePower(power_, -power_); + } + + void end(bool interrupted) override { + drive_->stop(); + Serial.printf("[Cmd] Turn bitti (interrupted=%d)\n", interrupted); + } + + bool isFinished() const override { + return (millis() - start_time_) >= duration_ms_; + } + +private: + probot::command::examples::TankDrive* drive_; + float power_; + uint32_t duration_ms_; + uint32_t start_time_ = 0; +}; + +// Global command instances +static DriveForwardCmd driveForward1(&chassis, 0.5f, 2500); +static WaitCommand pause1(800); +static TurnCmd turn90(&chassis, 0.4f, 2200); +static DriveForwardCmd driveToGoal(&chassis, 0.5f, 2000); + +// SequentialCommandGroup ile otonom sekans +static SequentialCommandGroup autoSequence("AutoSequence"); +static bool g_auto_built = false; + +void robotInit() { + Serial.begin(115200); + delay(100); + + leftMotor.begin(); + rightMotor.begin(); + leftMotor.setBrakeMode(true); + rightMotor.setBrakeMode(true); + + // NOTE: Closed-loop/odometry helpers are disabled (not tested yet). + // chassis.setWheelRadius(32.0f / (2.0f * 3.1415926535f)); + // chassis.setTrackWidth(29.0f); + + // Otonom sekansini olustur: Ileri -> Bekle -> Don -> Ileri + if (!g_auto_built) { + autoSequence.addCommands(&driveForward1, &pause1, &turn90, &driveToGoal); + g_auto_built = true; + } + + // Subsystem'i kaydet + Scheduler::instance().registerSubsystem(&chassis); + Serial.println("[AutonomousDemo] robotInit: Otonom ornegi hazir"); +} + +void robotEnd() { + Scheduler::instance().unregisterSubsystem(&chassis); + chassis.stop(); + Serial.println("[AutonomousDemo] robotEnd: Motorlar durdu"); +} + +void teleopInit() { + Serial.println("[AutonomousDemo] teleopInit: Bu ornekte teleop, tank surusu saglar"); +} + +void teleopLoop() { + auto js = probot::io::joystick_api::makeDefault(); + float leftAxis = js.getLeftY(); + float rightAxis = js.getRightY(); + chassis.drivePower(leftAxis, rightAxis); + delay(20); +} + +void autonomousInit() { + Serial.println("[AutonomousDemo] autonomousInit: SequentialCommandGroup ile otonom"); + Serial.println(" Sekans: Ileri(2.5s) -> Bekle(0.8s) -> Don(2.2s) -> Ileri(2s)"); + + // Otonom command'i schedule et + Scheduler::instance().schedule(&autoSequence); +} + +void autonomousLoop() { + // Command-based sistemde autonomousLoop bos kalabilir + // Tum is scheduler tarafindan yapiliyor + delay(20); +} diff --git a/examples/command_based/MecanumDriveDemo/MecanumDriveDemo.ino b/examples/command_based/MecanumDriveDemo/MecanumDriveDemo.ino new file mode 100644 index 0000000..da68b98 --- /dev/null +++ b/examples/command_based/MecanumDriveDemo/MecanumDriveDemo.ino @@ -0,0 +1,98 @@ +#define PROBOT_WIFI_AP_PASSWORD "ProBot1234" + +#include +#include +#include // Includes scheduler, command, subsystem, command_group +#include +#include + +// Mecanum surus icin dort motorun pin atamalari. +struct MotorPins { + int ina, inb, pwm, ena, enb; +}; + +static constexpr MotorPins PINS_FL{18, 19, 20, -1, -1}; +static constexpr MotorPins PINS_FR{21, 22, 23, -1, -1}; +static constexpr MotorPins PINS_RL{24, 25, 26, -1, -1}; +static constexpr MotorPins PINS_RR{27, 28, 29, -1, -1}; + +static probot::motor::BoardozaVNH5019MotorController drvFL(PINS_FL.ina, PINS_FL.inb, PINS_FL.pwm, PINS_FL.ena, PINS_FL.enb); +static probot::motor::BoardozaVNH5019MotorController drvFR(PINS_FR.ina, PINS_FR.inb, PINS_FR.pwm, PINS_FR.ena, PINS_FR.enb); +static probot::motor::BoardozaVNH5019MotorController drvRL(PINS_RL.ina, PINS_RL.inb, PINS_RL.pwm, PINS_RL.ena, PINS_RL.enb); +static probot::motor::BoardozaVNH5019MotorController drvRR(PINS_RR.ina, PINS_RR.inb, PINS_RR.pwm, PINS_RR.ena, PINS_RR.enb); + +static probot::command::examples::MecanumDrive mecanum(&drvFL, &drvFR, &drvRL, &drvRR); + +using Scheduler = probot::command::Scheduler; + +void robotInit() { + Serial.begin(115200); + delay(100); + + drvFL.begin(); drvFR.begin(); drvRL.begin(); drvRR.begin(); + drvFL.setBrakeMode(true); + drvFR.setBrakeMode(true); + drvRL.setBrakeMode(true); + drvRR.setBrakeMode(true); + + mecanum.setInverted(false, true, false, true); // sag taraf ters kabloluysa duzelt + mecanum.setWheelBase(30.0f); + mecanum.setTrackWidth(28.0f); + + // Yeni API: Subsystem'i scheduler'a kaydet + Scheduler::instance().registerSubsystem(&mecanum); + Serial.println("[MecanumDriveDemo] robotInit: Mecanum suruse hazir"); +} + +void robotEnd() { + Scheduler::instance().unregisterSubsystem(&mecanum); + mecanum.stop(); + Serial.println("[MecanumDriveDemo] robotEnd: Motorlar kapatildi"); +} + +void teleopInit() { + Serial.println("[MecanumDriveDemo] teleopInit:" + " sol cubuk Y ileri-geri, X yan, sag X donus"); +} + +void teleopLoop() { + auto js = probot::io::joystick_api::makeDefault(); + + float vx = js.getLeftY(); // ileri geri + float vy = js.getLeftX(); // yan hareket + float omega = js.getRightX();// donus + + mecanum.drivePower(vx, vy, omega); + + Serial.printf("[MecanumDriveDemo] vx=%.2f vy=%.2f w=%.2f fl=%.2f fr=%.2f rl=%.2f rr=%.2f\n", + vx, vy, omega, + drvFL.getPower(), drvFR.getPower(), + drvRL.getPower(), drvRR.getPower()); + + delay(20); +} + +void autonomousInit() { + Serial.println("[MecanumDriveDemo] autonomousInit: kare rota denemesi"); +} + +void autonomousLoop() { + static uint32_t start = millis(); + uint32_t elapsed = millis() - start; + float vx = 0.0f, vy = 0.0f, omega = 0.0f; + + if (elapsed < 2000) { + vx = 0.6f; // ileri + } else if (elapsed < 4000) { + vy = 0.6f; // saga kay + } else if (elapsed < 6000) { + vx = -0.6f; // geri + } else if (elapsed < 8000) { + vy = -0.6f; // sola kay + } else { + start = millis(); + } + + mecanum.drivePower(vx, vy, omega); + delay(20); +} diff --git a/examples/command_based/ShooterDemo/ShooterDemo.ino b/examples/command_based/ShooterDemo/ShooterDemo.ino new file mode 100644 index 0000000..5b5305a --- /dev/null +++ b/examples/command_based/ShooterDemo/ShooterDemo.ino @@ -0,0 +1,84 @@ +#define PROBOT_WIFI_AP_PASSWORD "ProBot1234" + +#include +#include +#include +#include + +// ============================================================================ +// Basit Shooter Subsystem (acik cevrim) +// ============================================================================ +class ShooterSubsystem : public probot::command::SubsystemBase { +public: + explicit ShooterSubsystem(probot::motor::IMotorController* motor) + : SubsystemBase("Shooter"), motor_(motor) {} + + void setPower(float power) { + power_ = constrain(power, 0.0f, 1.0f); // shooter sadece ileri doner + } + + float getPower() const { return power_; } + + void stop() { power_ = 0.0f; } + + void periodic(uint32_t, uint32_t) override { + if (motor_) motor_->setPower(power_); + } + +private: + probot::motor::IMotorController* motor_; + float power_ = 0.0f; +}; + +// ============================================================================ +// Hardware +// ============================================================================ +static constexpr int PIN_INA = 15; +static constexpr int PIN_INB = 16; +static constexpr int PIN_PWM = 17; + +static probot::motor::BoardozaVNH5019MotorController motor(PIN_INA, PIN_INB, PIN_PWM, -1, -1); +static ShooterSubsystem shooter(&motor); + +using Scheduler = probot::command::Scheduler; + +void robotInit() { + Serial.begin(115200); + motor.begin(); + motor.setBrakeMode(false); // shooter coast modunda + + Scheduler::instance().registerSubsystem(&shooter); + Serial.println("[ShooterDemo] Shooter subsystem hazir"); +} + +void robotEnd() { + Scheduler::instance().unregisterSubsystem(&shooter); + shooter.stop(); + Serial.println("[ShooterDemo] Bitti"); +} + +void teleopInit() { + Serial.println("[ShooterDemo] Sag tetik hizlandirir, sol tetik durdurur"); +} + +void teleopLoop() { + auto js = probot::io::joystick_api::makeDefault(); + + float accel = js.getRightTriggerAxis(); + float brake = js.getLeftTriggerAxis(); + + float power = accel; + if (brake > 0.2f) power = 0.0f; + + shooter.setPower(power); + + probot::telemetry::printf("Shooter: %.2f\n", shooter.getPower()); +} + +void autonomousInit() { + shooter.stop(); +} + +void autonomousLoop() { + // Otonom sekans eklenebilir +} diff --git a/examples/command_based/SliderDemo/SliderDemo.ino b/examples/command_based/SliderDemo/SliderDemo.ino new file mode 100644 index 0000000..1c187b9 --- /dev/null +++ b/examples/command_based/SliderDemo/SliderDemo.ino @@ -0,0 +1,83 @@ +#define PROBOT_WIFI_AP_PASSWORD "ProBot1234" + +#include +#include +#include +#include + +// ============================================================================ +// Basit Slider Subsystem (acik cevrim) +// ============================================================================ +class SliderSubsystem : public probot::command::SubsystemBase { +public: + explicit SliderSubsystem(probot::motor::IMotorController* motor) + : SubsystemBase("Slider"), motor_(motor) {} + + void setPower(float power) { + power_ = constrain(power, -1.0f, 1.0f); + } + + float getPower() const { return power_; } + + void stop() { power_ = 0.0f; } + + void periodic(uint32_t, uint32_t) override { + if (motor_) motor_->setPower(power_); + } + +private: + probot::motor::IMotorController* motor_; + float power_ = 0.0f; +}; + +// ============================================================================ +// Hardware +// ============================================================================ +static constexpr int PIN_INA = 12; +static constexpr int PIN_INB = 13; +static constexpr int PIN_PWM = 14; + +static probot::motor::BoardozaVNH5019MotorController motor(PIN_INA, PIN_INB, PIN_PWM, -1, -1); +static SliderSubsystem slider(&motor); + +using Scheduler = probot::command::Scheduler; + +void robotInit() { + Serial.begin(115200); + motor.begin(); + motor.setBrakeMode(true); + + Scheduler::instance().registerSubsystem(&slider); + Serial.println("[SliderDemo] Slider subsystem hazir"); +} + +void robotEnd() { + Scheduler::instance().unregisterSubsystem(&slider); + slider.stop(); + Serial.println("[SliderDemo] Bitti"); +} + +void teleopInit() { + Serial.println("[SliderDemo] D-pad yukari/asagi ile slider kontrol edin"); +} + +void teleopLoop() { + auto js = probot::io::joystick_api::makeDefault(); + int pov = js.getPOV(); + + float cmd = 0.0f; + if (pov == 0) cmd = 0.6f; // yukari + if (pov == 180) cmd = -0.6f; // asagi + + slider.setPower(cmd); + + probot::telemetry::printf("Slider: %.2f\n", slider.getPower()); +} + +void autonomousInit() { + slider.stop(); +} + +void autonomousLoop() { + // Otonom sekans eklenebilir +} diff --git a/examples/command_based/TankDriveDemo/TankDriveDemo.ino b/examples/command_based/TankDriveDemo/TankDriveDemo.ino new file mode 100644 index 0000000..85135ac --- /dev/null +++ b/examples/command_based/TankDriveDemo/TankDriveDemo.ino @@ -0,0 +1,105 @@ +#define PROBOT_WIFI_AP_PASSWORD "ProBot1234" + +#include +#include +#include // Includes scheduler, command, subsystem, command_group +#include +#include + +// Tank sasi icin iki adet VNH motor kontrolcusunun pin eslemesi (ornek degerler). +static constexpr int LEFT_INA = 1; +static constexpr int LEFT_INB = 2; +static constexpr int LEFT_PWM = 3; +static constexpr int LEFT_ENA = -1; +static constexpr int LEFT_ENB = -1; + +static constexpr int RIGHT_INA = 4; +static constexpr int RIGHT_INB = 5; +static constexpr int RIGHT_PWM = 6; +static constexpr int RIGHT_ENA = -1; +static constexpr int RIGHT_ENB = -1; + +static probot::motor::BoardozaVNH5019MotorController leftMotor(LEFT_INA, LEFT_INB, LEFT_PWM, LEFT_ENA, LEFT_ENB); +static probot::motor::BoardozaVNH5019MotorController rightMotor(RIGHT_INA, RIGHT_INB, RIGHT_PWM, RIGHT_ENA, RIGHT_ENB); +static probot::command::examples::TankDrive chassis(&leftMotor, &rightMotor); + +using Scheduler = probot::command::Scheduler; + +void robotInit() { + Serial.begin(115200); + delay(100); + + leftMotor.begin(); + rightMotor.begin(); + leftMotor.setBrakeMode(true); + rightMotor.setBrakeMode(true); + + // NOTE: Closed-loop/odometry helpers are disabled (not tested yet). + // chassis.setWheelRadius(31.4f / (2.0f * 3.1415926535f)); // cm cinsinden yaricap + // chassis.setTrackWidth(28.0f); // cm + + // Yeni API: Subsystem'i scheduler'a kaydet + Scheduler::instance().registerSubsystem(&chassis); + Serial.println("[TankDriveDemo] robotInit: Tank sasi hazir"); +} + +void robotEnd() { + Scheduler::instance().unregisterSubsystem(&chassis); + chassis.stop(); + Serial.println("[TankDriveDemo] robotEnd: Motorlar kapandi"); +} + +void teleopInit() { + Serial.println("[TankDriveDemo] teleopInit: Sol/Sag joystick ile tank surusu"); +} + +void teleopLoop() { + auto js = probot::io::joystick_api::makeDefault(); + + float leftAxis = js.getLeftY(); + float rightAxis = js.getRightY(); + chassis.drivePower(leftAxis, rightAxis); + + Serial.printf("[TankDriveDemo] left=%.2f right=%.2f outL=%.2f outR=%.2f\n", + leftAxis, rightAxis, + leftMotor.getPower(), rightMotor.getPower()); + + delay(20); +} + +void autonomousInit() { + Serial.println("[TankDriveDemo] autonomousInit: 3 adimda ilerleme testi"); +} + +void autonomousLoop() { + static uint32_t stateStart = millis(); + static int state = 0; + + uint32_t now = millis(); + switch (state) { + case 0: // 1 metre ileri + chassis.drivePower(0.5f, 0.5f); + if (now - stateStart > 3000) { + stateStart = now; + state = 1; + } + break; + case 1: + chassis.drivePower(0.4f, -0.4f); + if (now - stateStart > 2000) { + stateStart = now; + state = 2; + } + break; + case 2: + chassis.drivePower(0.5f, 0.5f); + if (now - stateStart > 2000) { + state = 3; + } + break; + default: + chassis.stop(); + break; + } + delay(20); +} diff --git a/examples/command_based/TurretDemo/TurretDemo.ino b/examples/command_based/TurretDemo/TurretDemo.ino new file mode 100644 index 0000000..02fa177 --- /dev/null +++ b/examples/command_based/TurretDemo/TurretDemo.ino @@ -0,0 +1,81 @@ +#define PROBOT_WIFI_AP_PASSWORD "ProBot1234" + +#include +#include +#include +#include + +// ============================================================================ +// Basit Turret Subsystem (acik cevrim) +// ============================================================================ +class TurretSubsystem : public probot::command::SubsystemBase { +public: + explicit TurretSubsystem(probot::motor::IMotorController* motor) + : SubsystemBase("Turret"), motor_(motor) {} + + void setPower(float power) { + power_ = constrain(power, -1.0f, 1.0f); + } + + float getPower() const { return power_; } + + void stop() { power_ = 0.0f; } + + void periodic(uint32_t, uint32_t) override { + if (motor_) motor_->setPower(power_); + } + +private: + probot::motor::IMotorController* motor_; + float power_ = 0.0f; +}; + +// ============================================================================ +// Hardware +// ============================================================================ +static constexpr int PIN_INA = 30; +static constexpr int PIN_INB = 31; +static constexpr int PIN_PWM = 32; + +static probot::motor::BoardozaVNH5019MotorController motor(PIN_INA, PIN_INB, PIN_PWM, -1, -1); +static TurretSubsystem turret(&motor); + +using Scheduler = probot::command::Scheduler; + +void robotInit() { + Serial.begin(115200); + motor.begin(); + motor.setBrakeMode(true); + + Scheduler::instance().registerSubsystem(&turret); + Serial.println("[TurretDemo] Turret subsystem hazir"); +} + +void robotEnd() { + Scheduler::instance().unregisterSubsystem(&turret); + turret.stop(); + Serial.println("[TurretDemo] Bitti"); +} + +void teleopInit() { + Serial.println("[TurretDemo] Sag stick X ile taret dondur, B ile durdur"); +} + +void teleopLoop() { + auto js = probot::io::joystick_api::makeDefault(); + + float cmd = js.getRightX(); + if (js.getB()) cmd = 0.0f; // B butonu durdurur + + turret.setPower(cmd); + + probot::telemetry::printf("Turret: %.2f\n", turret.getPower()); +} + +void autonomousInit() { + turret.stop(); +} + +void autonomousLoop() { + // Otonom sekans eklenebilir +} diff --git a/idf_component.yml b/idf_component.yml index d0bcdef..5f5e841 100644 --- a/idf_component.yml +++ b/idf_component.yml @@ -1,4 +1,4 @@ -version: 0.1.4 +version: 0.2.0 description: ESP32-S3 robotics control library url: https://github.com/nfrproducts/probot-lib dependencies: diff --git a/library.json b/library.json index bd208ee..06d3e21 100644 --- a/library.json +++ b/library.json @@ -26,5 +26,5 @@ "type": "git", "url": "https://github.com/nfrproducts/probot-lib" }, - "version": "0.1.5" + "version": "0.2.0" } diff --git a/library.properties b/library.properties index 2643abc..c639468 100644 --- a/library.properties +++ b/library.properties @@ -1,5 +1,5 @@ name=probot -version=0.1.5 +version=0.2.0 author=Tuna Gül maintainer=Tuna Gül sentence=ProBot Library for Robotics Competitions. diff --git a/src/core/runtime.cpp b/src/core/runtime.cpp deleted file mode 100644 index 89a3ab4..0000000 --- a/src/core/runtime.cpp +++ /dev/null @@ -1,112 +0,0 @@ -#include -#include -#include -#include -#include -#include -#include -#include - -#if PROBOT_WITH_DS && defined(ESP32) -#ifndef PROBOT_WIFI_AP_PASSWORD -extern const char* PROBOT__DS_PASSWORD_REQUIRED; -#endif -#endif - -namespace probot { - static TaskHandle_t hUi=nullptr, hCtrl=nullptr, hUser=nullptr; - static TaskHandle_t hAuto=nullptr, hTeleop=nullptr; - - extern void uiTask(void*); - - static void autonomousWorker(void*){ - for(;;){ ::autonomousLoop(); vTaskDelay(pdMS_TO_TICKS(1)); } - } - static void teleopWorker(void*){ - for(;;){ ::teleopLoop(); vTaskDelay(pdMS_TO_TICKS(1)); } - } - - static void stopAutonomous(){ if (hAuto){ vTaskDelete(hAuto); hAuto=nullptr; } } - static void stopTeleop(){ if (hTeleop){ vTaskDelete(hTeleop); hTeleop=nullptr; } } - static void startAutonomous(){ stopTeleop(); stopAutonomous(); xTaskCreatePinnedToCore(autonomousWorker, "auto", STACK_USER, NULL, PRIO_USER, &hAuto, CORE_CTRL); } - static void startTeleop(){ stopAutonomous(); stopTeleop(); xTaskCreatePinnedToCore(teleopWorker, "teleop", STACK_USER, NULL, PRIO_USER, &hTeleop, CORE_CTRL); } - - static void updateLed(){ - auto s = probot::robot::state().read(); - static bool on=false; on=!on; - static uint32_t deadlineMissTime = 0; - - // Show deadline miss for 2 seconds (4 blinks) then auto-clear - if (s.deadlineMiss){ - if (deadlineMissTime == 0) deadlineMissTime = millis(); - if (millis() - deadlineMissTime > 2000){ - probot::robot::state().setDeadlineMiss(millis(), false); - deadlineMissTime = 0; - } else { - // Blink red - if (on) builtinled::setColor(255,0,0); - else builtinled::setColor(0,0,0); - return; - } - } else { - deadlineMissTime = 0; - } - - switch (s.phase){ - case probot::robot::Phase::NOT_INIT: - if (s.clientCount > 0){ if (on) builtinled::setColor(0,0,255); else builtinled::setColor(0,0,0); } - else { builtinled::setColor(0,0,255); } - break; - case probot::robot::Phase::INITED: - builtinled::setColor(255,255,0); - break; - case probot::robot::Phase::AUTONOMOUS: - if (on) builtinled::setColor(255,128,0); else builtinled::setColor(0,0,0); - break; - case probot::robot::Phase::TELEOP: - if (on) builtinled::setColor(0,255,0); else builtinled::setColor(0,0,0); - break; - } - } - - static void userLoopTask(){ - using probot::robot::Status; using probot::robot::Phase; - bool inited=false; bool inTeleop=false; bool inAuto=false; uint32_t autoStartWallMs=0; int32_t autoLen=0; uint32_t lastLed=0; - for(;;){ - auto s = probot::robot::state().read(); - if (!inited && s.status == Status::INIT){ ::robotInit(); inited=true; inTeleop=false; inAuto=false; probot::robot::state().setPhase(millis(), Phase::INITED); } - if (s.status == Status::START){ - if (s.autonomousEnabled){ - if (!inAuto){ ::autonomousInit(); inAuto=true; inTeleop=false; autoStartWallMs = millis(); autoLen = s.autoPeriodSeconds; probot::robot::state().setPhase(millis(), Phase::AUTONOMOUS); startAutonomous(); } - uint32_t now = millis(); - if (autoLen>0 && (int32_t)(now - autoStartWallMs) >= autoLen*1000){ - stopAutonomous(); ::teleopInit(); inTeleop=true; inAuto=false; probot::robot::state().setPhase(millis(), Phase::TELEOP); probot::robot::state().setAutonomous(millis(), false); startTeleop(); - } - } else { - if (!inTeleop){ ::teleopInit(); inTeleop=true; inAuto=false; probot::robot::state().setPhase(millis(), Phase::TELEOP); startTeleop(); } - } - } else if (s.status == Status::STOP){ - if (inited){ stopAutonomous(); stopTeleop(); ::robotEnd(); inited=false; inTeleop=false; inAuto=false; probot::robot::state().setPhase(millis(), Phase::NOT_INIT); } - } - uint32_t now=millis(); if (now - lastLed >= 500){ lastLed = now; updateLed(); } - vTaskDelay(pdMS_TO_TICKS(1)); - } - } - - void runtime_setup(){ - Serial.begin(115200); - delay(200); - Serial.println("\n[PROBOT] Core0=UI+INPUT, Core1=CTRL(high)+USER(low)"); - - wdt_init_no_idle(3, true); - control::init(8); - -#if PROBOT_WITH_DS && defined(ESP32) - probot::platform::start_driver_station(); -#endif - - xTaskCreatePinnedToCore(uiTask, "ui", STACK_UI, NULL, PRIO_UI, &hUi, CORE_UI); - xTaskCreatePinnedToCore(control::schedulerTask, "ctrl", STACK_CTRL, NULL, PRIO_CTRL, &hCtrl, CORE_CTRL); - xTaskCreatePinnedToCore([](void*){ userLoopTask(); }, "user", STACK_USER, NULL, PRIO_USER, &hUser, CORE_CTRL); - } -} \ No newline at end of file diff --git a/src/core/scheduler.cpp b/src/core/scheduler.cpp deleted file mode 100644 index 102cd5b..0000000 --- a/src/core/scheduler.cpp +++ /dev/null @@ -1,207 +0,0 @@ -#include -#include -#include -#include -#include -#include -#include - -namespace control { - enum CmdType : uint8_t { CMD_ATTACH=0, CMD_DETACH=1 }; - struct Cmd { - CmdType type; - IUpdatable* obj; - }; - - QueueHandle_t qCmd = nullptr; - - struct Slot { - bool in_use; - IUpdatable* obj; - uint32_t next_due_ms; - uint32_t last_call_ms; - }; - - static const size_t MAX_SLOTS = 512; - static Slot slots[MAX_SLOTS]; - static uint32_t g_global_period_ms = 20; - - void setGlobalPeriodMs(uint32_t period_ms){ - if (period_ms == 0) return; - g_global_period_ms = period_ms; - } - - void init(uint8_t queue_len){ - if (!qCmd){ - qCmd = xQueueCreate(queue_len, sizeof(Cmd)); - } - probot::logging::configureDefaults(); - } - - static int find_slot(IUpdatable* obj){ - for (int i=0;i<(int)MAX_SLOTS;i++){ - if (slots[i].in_use && slots[i].obj == obj) return i; - } - return -1; - } - static int find_free_slot(){ - for (int i=0;i<(int)MAX_SLOTS;i++){ - if (!slots[i].in_use) return i; - } - return -1; - } - - bool attach(IUpdatable* obj){ - if (!qCmd || !obj) return false; - Cmd c{CMD_ATTACH, obj}; - return xQueueSend(qCmd, &c, pdMS_TO_TICKS(10)) == pdTRUE; - } - - bool detach(IUpdatable* obj){ - if (!qCmd || !obj) return false; - Cmd c{CMD_DETACH, obj}; - return xQueueSend(qCmd, &c, pdMS_TO_TICKS(10)) == pdTRUE; - } - - size_t count(){ - size_t n=0; - for (size_t i=0;i= 5 - esp_task_wdt_add(NULL); -#endif - for (size_t i=0;i= 0){ - slots[idx].in_use = true; - auto wrapped = probot::logging::wrapForScheduler(cmd.obj); - slots[idx].obj = wrapped; - uint32_t t = millis(); - slots[idx].last_call_ms = t; - slots[idx].next_due_ms = t + g_global_period_ms; -#ifndef PROBOT_SCHED_NOLOG - Serial.printf("[CMD ] attach ok (idx=%d, period=%lums)\n", idx, (unsigned long)g_global_period_ms); -#endif - } else { -#ifndef PROBOT_SCHED_NOLOG - Serial.println("[CMD ] attach FAILED (no free slot)"); -#endif - } - } else { - auto wrapped = probot::logging::resolveForDetach(cmd.obj); - int idx = find_slot(wrapped); - if (idx >= 0){ - slots[idx] = {false, nullptr, 0, 0}; - probot::logging::releaseForDetach(cmd.obj); -#ifndef PROBOT_SCHED_NOLOG - Serial.printf("[CMD ] detach ok (idx=%d)\n", idx); -#endif - } else { -#ifndef PROBOT_SCHED_NOLOG - Serial.println("[CMD ] detach miss (not found)"); -#endif - } - } - } - - now = millis(); - uint32_t nearest_due = now + 1000; - bool deadlineMiss = false; - uint32_t maxOverrun = 0; - auto snap = probot::robot::state().read(); - bool allowUpdates = (snap.phase != probot::robot::Phase::NOT_INIT); - for (size_t i=0;i= 0){ - uint32_t dt = now - slots[i].last_call_ms; - if (dt > g_global_period_ms + 2){ - deadlineMiss = true; - uint32_t overrun = dt - g_global_period_ms; - if (overrun > maxOverrun) maxOverrun = overrun; - } - if (allowUpdates){ slots[i].obj->update(now, dt); } - slots[i].last_call_ms = now; - uint32_t due = slots[i].next_due_ms; - while ((int32_t)(now - due) >= 0){ - due += g_global_period_ms; - } - slots[i].next_due_ms = due; - } - if ((int32_t)(slots[i].next_due_ms - nearest_due) < 0){ - nearest_due = slots[i].next_due_ms; - } - } - if (deadlineMiss){ - probot::robot::state().setDeadlineMiss(now, true); - probot::logging::notifySchedulerOverrun(now, maxOverrun); -#ifndef PROBOT_SCHED_NOLOG - Serial.printf("[SCHED] ⚠️ CONTROL LOOP OVERRUN! Period: %lums, Overrun: +%lums\n", - (unsigned long)g_global_period_ms, (unsigned long)maxOverrun); -#endif - } - -#if ESP_IDF_VERSION_MAJOR >= 5 - esp_task_wdt_reset(); -#endif - - TickType_t waitTicks = pdMS_TO_TICKS(1); - now = millis(); - if ((int32_t)(nearest_due - now) > 0){ - waitTicks = pdMS_TO_TICKS(nearest_due - now); - } - if (xQueueReceive(qCmd, &cmd, waitTicks) == pdTRUE){ - if (cmd.type == CMD_ATTACH){ - auto existing = probot::logging::resolveForDetach(cmd.obj); - int idx = find_slot(existing); - if (idx < 0) idx = find_free_slot(); - if (idx >= 0){ - slots[idx].in_use = true; - auto wrapped = probot::logging::wrapForScheduler(cmd.obj); - slots[idx].obj = wrapped; - uint32_t t = millis(); - slots[idx].last_call_ms = t; - slots[idx].next_due_ms = t + g_global_period_ms; -#ifndef PROBOT_SCHED_NOLOG - Serial.printf("[CMD ] attach ok (idx=%d, period=%lums)\n", idx, (unsigned long)g_global_period_ms); -#endif - } else { -#ifndef PROBOT_SCHED_NOLOG - Serial.println("[CMD ] attach FAILED (no free slot)"); -#endif - } - } else { - auto wrapped = probot::logging::resolveForDetach(cmd.obj); - int idx = find_slot(wrapped); - if (idx >= 0){ - slots[idx] = {false, nullptr, 0, 0}; - probot::logging::releaseForDetach(cmd.obj); -#ifndef PROBOT_SCHED_NOLOG - Serial.printf("[CMD ] detach ok (idx=%d)\n", idx); -#endif - } else { -#ifndef PROBOT_SCHED_NOLOG - Serial.println("[CMD ] detach miss (not found)"); -#endif - } - } - } - } - } -} diff --git a/src/core/wdt.cpp b/src/core/wdt.cpp deleted file mode 100644 index 864c74a..0000000 --- a/src/core/wdt.cpp +++ /dev/null @@ -1,20 +0,0 @@ -#include -#include -#include -#include - -namespace probot { - void wdt_init_no_idle(uint32_t timeout_s, bool panic_on){ - esp_task_wdt_deinit(); -#if ESP_IDF_VERSION_MAJOR >= 5 - esp_task_wdt_config_t cfg = { - .timeout_ms = timeout_s * 1000, - .idle_core_mask = 0, - .trigger_panic = panic_on - }; - ESP_ERROR_CHECK( esp_task_wdt_init(&cfg) ); -#else - (void)timeout_s; (void)panic_on; -#endif - } -} \ No newline at end of file diff --git a/src/platform/esp32s3/web/driver_station_esp32.hpp b/src/driverstation/esp32s3/driver_station_esp32.hpp similarity index 57% rename from src/platform/esp32s3/web/driver_station_esp32.hpp rename to src/driverstation/esp32s3/driver_station_esp32.hpp index 11886d1..c9441a7 100644 --- a/src/platform/esp32s3/web/driver_station_esp32.hpp +++ b/src/driverstation/esp32s3/driver_station_esp32.hpp @@ -5,32 +5,22 @@ #include #include #include -#include +#include #include "index_html.h" -#if defined(PROBOT_WITH_DS) && !defined(PROBOT_WIFI_AP_PASSWORD) -#warning "DriverStation AP password not provided. Call PROBOT_SET_DRIVER_STATION_PASSWORD(\"yourpassword\") in your sketch (or define PROBOT_WIFI_AP_PASSWORD). If you already set it via the macro, you can ignore this warning." +#ifndef PROBOT_WIFI_AP_PASSWORD +#error "DriverStation AP password not provided. Define PROBOT_WIFI_AP_PASSWORD (>=8 chars) before including probot.h." #endif -#ifdef PROBOT_WIFI_AP_PASSWORD static_assert(sizeof(PROBOT_WIFI_AP_PASSWORD) - 1 >= 8, "PROBOT_WIFI_AP_PASSWORD must be at least 8 characters."); -#endif -namespace probot::platform::esp32 { +namespace probot::driverstation::esp32 { class DriverStation { public: - DriverStation(robot::StateService& rs, io::GamepadService& gs, const char* apPass = nullptr) - : _rs(rs), _gs(gs), _server(80), _apPass(apPass) {} + DriverStation(robot::StateService& rs, io::GamepadService& gs) + : _rs(rs), _gs(gs), _server(80) {} void begin(){ - const char* pw = nullptr; -#ifdef PROBOT_WIFI_AP_PASSWORD - pw = PROBOT_WIFI_AP_PASSWORD; -#endif - if (!pw) pw = _apPass; - if (!pw || strlen(pw) < 8){ - Serial.println("[DS ] AP password not set or too short; DriverStation AP disabled"); - return; - } + const char* pw = PROBOT_WIFI_AP_PASSWORD; String ssid = generateSSID(); ap_ssid_ = ssid; WiFi.mode(WIFI_AP); @@ -40,7 +30,7 @@ namespace probot::platform::esp32 { Serial.print("[DS ] WiFi SSID: "); Serial.println(ssid); Serial.print("[DS ] Password: "); - Serial.println(pw); + Serial.println("********"); Serial.print("[DS ] IP Address: "); Serial.println(WiFi.softAPIP()); Serial.println("[DS ] ========================================"); @@ -49,25 +39,52 @@ namespace probot::platform::esp32 { _server.on("/updateController", HTTP_POST, [this](){ if (!enforceOwner()) return; handleUpdateController(); }); _server.on("/robotControl", HTTP_GET, [this](){ if (!enforceOwner()) return; handleRobotControl(); }); _server.on("/getBattery", HTTP_GET, [this](){ handleGetBattery(); }); - _server.on("/logging/status", HTTP_GET, [this](){ handleLoggingStatus(); }); - _server.on("/logging/stream", HTTP_GET, [this](){ handleLoggingStream(); }); - _server.on("/logging/clear", HTTP_POST, [this](){ handleLoggingClear(); }); - _server.on("/logging/toggle", HTTP_POST, [this](){ handleLoggingToggle(); }); - _server.on("/logging/download", HTTP_GET, [this](){ handleLoggingDownload(); }); + _server.on("/telemetry", HTTP_GET, [this](){ if (!enforceOwner()) return; handleTelemetry(); }); _server.begin(); } - void handleClient(){ _server.handleClient(); } + void handleClient(){ + _server.handleClient(); + expireOwnerIfIdle(); + } private: bool enforceOwner(){ + uint32_t now = millis(); IPAddress ip = _server.client().remoteIP(); - if (!_owner_set){ _owner = ip; _owner_set = true; _rs.setClientCount(millis(), 1); return true; } - if (ip == _owner) return true; + if (_owner_set && _owner_timeout_ms > 0 && + (uint32_t)(now - _owner_last_ms) > _owner_timeout_ms){ + releaseOwner(now); + } + if (!_owner_set){ + _owner = ip; + _owner_set = true; + _owner_last_ms = now; + _rs.setClientCount(now, 1); + return true; + } + if (ip == _owner){ + _owner_last_ms = now; + return true; + } _server.send(403, "text/plain", "Another client is already connected."); return false; } + void expireOwnerIfIdle(){ + if (!_owner_set || _owner_timeout_ms == 0) return; + uint32_t now = millis(); + if ((uint32_t)(now - _owner_last_ms) > _owner_timeout_ms){ + releaseOwner(now); + } + } + + void releaseOwner(uint32_t now_ms){ + _owner_set = false; + _owner = IPAddress(); + _rs.setClientCount(now_ms, 0); + } + static bool parseFloatArray(const String& body, const char* key, float* out, uint32_t maxCount, uint32_t& written){ written = 0; int keyPos = body.indexOf(key); if (keyPos < 0) return false; int lb = body.indexOf('[', keyPos); if (lb < 0) return false; int rb = body.indexOf(']', lb); if (rb < 0) return false; @@ -136,76 +153,17 @@ namespace probot::platform::esp32 { _server.send(200, "text/plain", "OK"); } - void handleLoggingStatus(){ - probot::logging::LoggingStatus status{}; - probot::logging::loggingStatus(status); - String json = "{"; - bool wifiConnected = WiFi.getMode() != WIFI_MODE_NULL; - json += "\"connected\":"; - json += (wifiConnected ? "true" : "false"); - json += ",\"streaming\":"; - json += (status.wifi_streaming && wifiConnected ? "true" : "false"); - json += ",\"ssid\":\""; - json += ap_ssid_; - json += "\",\"ip\":\""; - json += WiFi.softAPIP().toString(); - json += "\",\"clients\":"; - json += WiFi.softAPgetStationNum(); - json += ",\"rate\":"; - float rate = 0.0f; - if (status.wifi_stream_start_ms > 0){ - uint32_t elapsed = millis() - status.wifi_stream_start_ms; - if (elapsed > 0){ - rate = (static_cast(status.wifi_bytes_sent) * 1000.0f) / static_cast(elapsed); - } - } - json += static_cast(rate); - json += ",\"serial_drop\":"; - json += status.serial_drop; - json += ",\"wifi_drop\":"; - json += status.wifi_drop; - json += ",\"detail\":\""; - json += (status.wifi_streaming ? "Streaming" : "Ready"); - json += "\"}"; - _server.send(200, "application/json", json); - } - - void handleLoggingStream(){ - int tail = 200; - if (_server.hasArg("tail")){ - tail = _server.arg("tail").toInt(); - if (tail < 0) tail = 0; - } - std::string buffer; - probot::logging::loggingStream(buffer, static_cast(tail)); - _server.send(200, "text/plain", buffer.c_str()); - } - - void handleLoggingClear(){ - probot::logging::clearLoggingStream(); - _server.send(200, "text/plain", "cleared"); - } - - void handleLoggingToggle(){ - String payload = _server.arg("plain"); - bool enable = payload.indexOf("stop") < 0; - probot::logging::setWifiStreamingEnabled(enable); - _server.send(200, "text/plain", enable ? "started" : "stopped"); - } - - void handleLoggingDownload(){ - std::string buffer; - probot::logging::loggingStream(buffer, 0); - _server.sendHeader("Content-Disposition", "attachment; filename=probot_logs.txt"); - _server.send(200, "text/plain", buffer.c_str()); + void handleTelemetry(){ + _server.send(200, "text/plain", probot::telemetry::getBuffer()); } robot::StateService& _rs; io::GamepadService& _gs; WebServer _server; - const char* _apPass; bool _owner_set=false; IPAddress _owner; + uint32_t _owner_last_ms=0; + uint32_t _owner_timeout_ms=5000; String ap_ssid_; }; } diff --git a/src/platform/esp32s3/web/index_html.h b/src/driverstation/esp32s3/index_html.h similarity index 64% rename from src/platform/esp32s3/web/index_html.h rename to src/driverstation/esp32s3/index_html.h index 1b7f63f..62d4779 100644 --- a/src/platform/esp32s3/web/index_html.h +++ b/src/driverstation/esp32s3/index_html.h @@ -10,7 +10,7 @@ const char MAIN_page[] PROGMEM = R"=====( - ProBot Minimal Stack + ProBot DriverStation - - -
ProBot Flight HUD
-
-
-
-
-
-
-
Status: INIT
-
-
-
- -
No Gamepad
-
-
Phase: Standby
-
-
- -
-
- AUTO MODE -
Switch autonomous drive
-
- -
-
- DURATION - -
- -
-
-
-

Joystick Telemetry

-
- -
-
No gamepad selected.
-
No axis data...
-
No button data...
-
-
- - - diff --git a/ui-testing/variants/archive/base.html b/ui-testing/variants/archive/base.html deleted file mode 100644 index 8d32759..0000000 --- a/ui-testing/variants/archive/base.html +++ /dev/null @@ -1,67 +0,0 @@ - - - - - ProBot UI - - - - -
-
-

Main Drive

-

Joystick Status: Not Connected

- -

-

-

-
-
-

Joystick Test

-

Connect one or more controllers, press a button to register them, then pick which to use: - -

-

Selected Gamepad Info

-
No gamepad selected.
-

Axes

-
No data yet...
-

Buttons

-
No data yet...
-
-
- - - diff --git a/ui-testing/variants/archive/circuit_glow.html b/ui-testing/variants/archive/circuit_glow.html deleted file mode 100644 index f4987c0..0000000 --- a/ui-testing/variants/archive/circuit_glow.html +++ /dev/null @@ -1,365 +0,0 @@ - - - - - ProBot Circuit Glow - - - -
-
-

Circuit Glow

- ProBot Control Mesh -
-
Standby
-
-
-
-

Drive Lattice

-
- -
- -
- Mode - -
-
-
- - - Set to match format -
-
- -

Joystick: Awaiting link...

-
-
-

Telemetry Weave

- -
No gamepad selected.
-
Axis lines idle...
-
Button lines idle...
-
-
- - - diff --git a/ui-testing/variants/archive/command_deck.html b/ui-testing/variants/archive/command_deck.html deleted file mode 100644 index 7ceda62..0000000 --- a/ui-testing/variants/archive/command_deck.html +++ /dev/null @@ -1,634 +0,0 @@ - - - - - ProBot Command Deck - - - -
-

ProBot Command Deck

- - -
Phase: Standby
-
-
-
-

- Match Control - - - Not Connected - -

-
00:30
-
- -
- - -
-
- - -
-
- -
-
-

Joystick Console

-
- - -
-
No gamepad selected.
-
No data yet...
-
No data yet...
-
-
- - - diff --git a/ui-testing/variants/archive/control_tower.html b/ui-testing/variants/archive/control_tower.html deleted file mode 100644 index 0ed02c9..0000000 --- a/ui-testing/variants/archive/control_tower.html +++ /dev/null @@ -1,352 +0,0 @@ - - - - - ProBot Control Tower - - - -
ProBot Control Tower
-
- -
-
- Match Operation - Driver Station Control Pane -
-
-
- - -
-
- -
- Enabled - -
-
-
-
-

Input Telemetry

-
No gamepad selected.
-
Axis data not streaming...
-
Button data not streaming...
-
-
-
- - - diff --git a/ui-testing/variants/archive/neon_grid.html b/ui-testing/variants/archive/neon_grid.html deleted file mode 100644 index 40d803b..0000000 --- a/ui-testing/variants/archive/neon_grid.html +++ /dev/null @@ -1,356 +0,0 @@ - - - - - ProBot Neon Grid - - - -
-
-

Neon Grid

- ProBot Control Sphere -
-
INIT
-
-
-
-

Match Vector

-
- -
- -
- Mode - -
-
-
- - - Set per match constraints -
-
- -

Joystick Status: Awaiting link

-
-
-

Input Matrix

- -
No gamepad selected.
-
Axis stream idle...
-
Button stream idle...
-
-
- - - diff --git a/ui-testing/variants/archive/pit_wall.html b/ui-testing/variants/archive/pit_wall.html deleted file mode 100644 index 02cf174..0000000 --- a/ui-testing/variants/archive/pit_wall.html +++ /dev/null @@ -1,433 +0,0 @@ - - - - - ProBot Pit Wall - - - -
-

ProBot Pit Wall

- -
-
- PHASE - Standby -
-
- JOYSTICK - No Link -
-
- BATTERY - --.- V -
-
-
-
-
-

Match Control INIT

-
- -
- - -
-
- - - Match rule default: 30s -
-
- -
-
-

Joystick Telemetry

- -
No gamepad selected.
-
No axis data...
-
No button data...
-
-
- - - diff --git a/ui-testing/variants/archive/retro_terminal.html b/ui-testing/variants/archive/retro_terminal.html deleted file mode 100644 index e2ba12a..0000000 --- a/ui-testing/variants/archive/retro_terminal.html +++ /dev/null @@ -1,287 +0,0 @@ - - - - - ProBot Retro Terminal - - - -
ProBot Retro Terminal
-
-
-

Match Console

-
- PHASE: INIT - JOYSTICK: NONE -
-
-
- - -
-
- - - -
-
- - -
-
-
-
-

Input Feed

- -
No gamepad selected.
-
Axis feed idle...
-
Buttons idle...
-
-
- - - diff --git a/ui-testing/variants/archive/zen_flow.html b/ui-testing/variants/archive/zen_flow.html deleted file mode 100644 index ccaf730..0000000 --- a/ui-testing/variants/archive/zen_flow.html +++ /dev/null @@ -1,359 +0,0 @@ - - - - - ProBot Zen Flow - - - -
-
-

Zen Flow Control

- Balanced driver station -
-
Standby
-
-
-
-

Match Overview

-
-
Robot Command
-
Autonomous
-
Telemetry
-
- -
-
- - - Match default 30s -
-
- -
- Enabled - -
- -
-
-
Joystick Status: Disconnected
-
-
-

Input Telemetry

- -
No gamepad selected.
-
Axis data pending...
-
Button data pending...
-
-
- - - diff --git a/ui-testing/variants/minimal_stack.html b/ui-testing/variants/minimal_stack.html deleted file mode 100644 index d1976b2..0000000 --- a/ui-testing/variants/minimal_stack.html +++ /dev/null @@ -1,1458 +0,0 @@ - - - - - ProBot Driver Station - - - -
-
-

ProBot Driver Station

- by NFR Products · c2025 -
- -
- Status - Standby - Awaiting command -
-
-
-
-
-

Match Control

-
- -
- - - Seconds -
-
- Autonomous - -
-
-
-
- Autonomous Countdown - 00.0 s -
-
-
-
-
-
-
-

Joystick Check

-
-
-
-
-
-
- Axes -
-
-
-
- Not Connected - -
-
-
-
-
-

Wi-Fi Logging

-
- Disconnected - Waiting for Wi-Fi module... -
-
-
- Network - -
-
- Robot IP - -
-
- Clients - 0 -
-
- Rate - 0 KB/s -
-
-
- - - -
-
- - - Last sync: never -
-
-
-

System Logs

- -
No gamepad selected.
-
No axis data...
-
No button data...
-
-
- Wi-Fi Log Stream - -
-
Waiting for log data...
-
-
-
-
- - -