From 6ef931137aa23bc30eee7aaa68de4cf57b76c0dc Mon Sep 17 00:00:00 2001 From: tunapro Date: Thu, 25 Dec 2025 07:36:37 +0300 Subject: [PATCH 01/14] feat: add connection timeouts and fix thread safety issues --- .gitignore | 1 + VERSION | 2 +- examples/AutonomousDemo/AutonomousDemo.ino | 5 ++- examples/JoystickTest/JoystickTest.ino | 3 +- .../MecanumDriveDemo/MecanumDriveDemo.ino | 9 +++-- .../MotorControllerDemo.ino | 3 +- examples/MotorDriverDemo/MotorDriverDemo.ino | 3 +- examples/ShooterDemo/ShooterDemo.ino | 3 +- examples/SliderDemo/SliderDemo.ino | 3 +- examples/TankDriveDemo/TankDriveDemo.ino | 5 ++- examples/TurretDemo/TurretDemo.ino | 3 +- idf_component.yml | 2 +- library.json | 2 +- library.properties | 2 +- src/io/ui_input.cpp | 19 ++++++--- .../esp32s3/web/driver_station_esp32.hpp | 39 +++++++++++++++++-- src/platform/esp32s3/web/index_html.h | 5 +-- src/probot.h | 13 ------- src/probot/chassis/basic_tank_drive.hpp | 1 - src/probot/io/gamepad.hpp | 29 ++++++++++++-- src/probot/io/joystick_mappings/mapping.hpp | 15 +++---- src/probot/robot/state.hpp | 15 ++++++- tests/test_io.cpp | 4 ++ 23 files changed, 131 insertions(+), 55 deletions(-) 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/VERSION b/VERSION index 845639e..c946ee6 100644 --- a/VERSION +++ b/VERSION @@ -1 +1 @@ -0.1.4 +0.1.6 diff --git a/examples/AutonomousDemo/AutonomousDemo.ino b/examples/AutonomousDemo/AutonomousDemo.ino index 1da665d..b4ac84c 100644 --- a/examples/AutonomousDemo/AutonomousDemo.ino +++ b/examples/AutonomousDemo/AutonomousDemo.ino @@ -1,4 +1,5 @@ #include +#include #include #include #include @@ -20,8 +21,8 @@ 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 probot::test::NullEncoder leftEncoder; +static probot::test::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}; diff --git a/examples/JoystickTest/JoystickTest.ino b/examples/JoystickTest/JoystickTest.ino index a932644..296d1d0 100644 --- a/examples/JoystickTest/JoystickTest.ino +++ b/examples/JoystickTest/JoystickTest.ino @@ -1,4 +1,5 @@ #include +#include #include #include #include @@ -13,7 +14,7 @@ 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 probot::test::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); diff --git a/examples/MecanumDriveDemo/MecanumDriveDemo.ino b/examples/MecanumDriveDemo/MecanumDriveDemo.ino index d38ce88..f822ea1 100644 --- a/examples/MecanumDriveDemo/MecanumDriveDemo.ino +++ b/examples/MecanumDriveDemo/MecanumDriveDemo.ino @@ -1,4 +1,5 @@ #include +#include #include #include #include @@ -20,10 +21,10 @@ static probot::motor::BoardozaVNHMotorDriver drvFR(PINS_FR.ina, PINS_FR.inb, PIN 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 probot::test::NullEncoder encFL; +static probot::test::NullEncoder encFR; +static probot::test::NullEncoder encRL; +static probot::test::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}; diff --git a/examples/MotorControllerDemo/MotorControllerDemo.ino b/examples/MotorControllerDemo/MotorControllerDemo.ino index e975818..9b6dceb 100644 --- a/examples/MotorControllerDemo/MotorControllerDemo.ino +++ b/examples/MotorControllerDemo/MotorControllerDemo.ino @@ -1,4 +1,5 @@ #include +#include #include #include #include @@ -12,7 +13,7 @@ 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 probot::test::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); diff --git a/examples/MotorDriverDemo/MotorDriverDemo.ino b/examples/MotorDriverDemo/MotorDriverDemo.ino index 625166e..1af78c9 100644 --- a/examples/MotorDriverDemo/MotorDriverDemo.ino +++ b/examples/MotorDriverDemo/MotorDriverDemo.ino @@ -1,4 +1,5 @@ #include +#include #include #include #include @@ -12,7 +13,7 @@ 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 probot::test::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); diff --git a/examples/ShooterDemo/ShooterDemo.ino b/examples/ShooterDemo/ShooterDemo.ino index 7a69c92..b120c30 100644 --- a/examples/ShooterDemo/ShooterDemo.ino +++ b/examples/ShooterDemo/ShooterDemo.ino @@ -1,4 +1,5 @@ #include +#include #include #include #include @@ -13,7 +14,7 @@ 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 probot::test::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); diff --git a/examples/SliderDemo/SliderDemo.ino b/examples/SliderDemo/SliderDemo.ino index 2263d28..645beea 100644 --- a/examples/SliderDemo/SliderDemo.ino +++ b/examples/SliderDemo/SliderDemo.ino @@ -1,4 +1,5 @@ #include +#include #include #include #include @@ -13,7 +14,7 @@ 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 probot::test::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); diff --git a/examples/TankDriveDemo/TankDriveDemo.ino b/examples/TankDriveDemo/TankDriveDemo.ino index 9225314..2093225 100644 --- a/examples/TankDriveDemo/TankDriveDemo.ino +++ b/examples/TankDriveDemo/TankDriveDemo.ino @@ -1,4 +1,5 @@ #include +#include #include #include #include @@ -20,8 +21,8 @@ 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 probot::test::NullEncoder leftEncoder; +static probot::test::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}; diff --git a/examples/TurretDemo/TurretDemo.ino b/examples/TurretDemo/TurretDemo.ino index 25e248f..5224212 100644 --- a/examples/TurretDemo/TurretDemo.ino +++ b/examples/TurretDemo/TurretDemo.ino @@ -1,4 +1,5 @@ #include +#include #include #include #include @@ -13,7 +14,7 @@ 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 probot::test::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); diff --git a/idf_component.yml b/idf_component.yml index d0bcdef..d959c47 100644 --- a/idf_component.yml +++ b/idf_component.yml @@ -1,4 +1,4 @@ -version: 0.1.4 +version: 0.1.6 description: ESP32-S3 robotics control library url: https://github.com/nfrproducts/probot-lib dependencies: diff --git a/library.json b/library.json index bd208ee..4241ba0 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.1.6" } diff --git a/library.properties b/library.properties index 2643abc..f821f0a 100644 --- a/library.properties +++ b/library.properties @@ -1,5 +1,5 @@ name=probot -version=0.1.5 +version=0.1.6 author=Tuna Gül maintainer=Tuna Gül sentence=ProBot Library for Robotics Competitions. diff --git a/src/io/ui_input.cpp b/src/io/ui_input.cpp index e30dd21..d2b03cc 100644 --- a/src/io/ui_input.cpp +++ b/src/io/ui_input.cpp @@ -1,6 +1,7 @@ #include #include #include +#include namespace probot { static UiState g_ui_buf[2]; @@ -11,6 +12,11 @@ namespace probot { static inline void atomic_store_u32(volatile uint32_t* p, uint32_t v){ __atomic_store_n(p, v, __ATOMIC_SEQ_CST); } static inline uint32_t atomic_load_u32(volatile uint32_t* p){ return __atomic_load_n(p, __ATOMIC_SEQ_CST); } + static inline int16_t clamp_axis_i16(float v){ + if (v > 1.0f) v = 1.0f; + else if (v < -1.0f) v = -1.0f; + return static_cast(v * 32767.0f); + } UiState read_ui_snapshot(){ uint32_t idx = atomic_load_u32(&g_ui_cur_idx); @@ -41,18 +47,19 @@ namespace probot { } if (now - last_in >= 10){ - uint32_t prev_in = last_in; last_in = now; uint32_t cur = atomic_load_u32(&g_in_cur_idx); uint32_t w = 1u - cur; - static bool btn = false; - if ((now / 1000u) != (prev_in / 1000u)) btn = !btn; + auto snap = probot::io::gamepad().read(); + float x = (snap.axisCount > 0) ? snap.axes[0] : 0.0f; + float y = (snap.axisCount > 1) ? snap.axes[1] : 0.0f; + bool btn = (snap.buttonCount > 0) ? snap.buttons[0] : false; g_in_buf[w].seq = ++in_seq; g_in_buf[w].ms = now; - g_in_buf[w].x = 0; - g_in_buf[w].y = 0; + g_in_buf[w].x = clamp_axis_i16(x); + g_in_buf[w].y = clamp_axis_i16(y); g_in_buf[w].btn = btn ? 1 : 0; __atomic_thread_fence(__ATOMIC_SEQ_CST); atomic_store_u32(&g_in_cur_idx, w); @@ -61,4 +68,4 @@ namespace probot { vTaskDelay(pdMS_TO_TICKS(1)); } } -} \ No newline at end of file +} diff --git a/src/platform/esp32s3/web/driver_station_esp32.hpp b/src/platform/esp32s3/web/driver_station_esp32.hpp index 11886d1..6fb955c 100644 --- a/src/platform/esp32s3/web/driver_station_esp32.hpp +++ b/src/platform/esp32s3/web/driver_station_esp32.hpp @@ -57,17 +57,48 @@ namespace probot::platform::esp32 { _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; @@ -206,6 +237,8 @@ namespace probot::platform::esp32 { 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/platform/esp32s3/web/index_html.h index 1b7f63f..03fec49 100644 --- a/src/platform/esp32s3/web/index_html.h +++ b/src/platform/esp32s3/web/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...
-
-
-
-
- - - From c1a7b30d2b2fb1e2d5332e2243626a7f15370646 Mon Sep 17 00:00:00 2001 From: tunapro Date: Thu, 1 Jan 2026 21:47:40 +0300 Subject: [PATCH 11/14] disable mechanisms --- .../AutonomousDemo/AutonomousDemo.ino | 5 +- .../TankDriveDemo/TankDriveDemo.ino | 5 +- src/probot/command/examples/arm.hpp | 3 + src/probot/command/examples/elevator.hpp | 3 + src/probot/command/examples/mecanum_drive.hpp | 72 ++++++++++++++++++- src/probot/command/examples/slider.hpp | 3 + src/probot/command/examples/tank_drive.hpp | 45 +++++++++++- .../command/examples/telescopic_tube.hpp | 3 + src/probot/command/examples/turret.hpp | 3 + src/probot/command/scheduler.hpp | 12 ++++ tests/test_chassis.cpp | 5 ++ tests/test_mechanisms.cpp | 3 + 12 files changed, 156 insertions(+), 6 deletions(-) diff --git a/examples/command_based/AutonomousDemo/AutonomousDemo.ino b/examples/command_based/AutonomousDemo/AutonomousDemo.ino index f2607d0..9cfb1e4 100644 --- a/examples/command_based/AutonomousDemo/AutonomousDemo.ino +++ b/examples/command_based/AutonomousDemo/AutonomousDemo.ino @@ -115,8 +115,9 @@ void robotInit() { leftMotor.setBrakeMode(true); rightMotor.setBrakeMode(true); - chassis.setWheelRadius(32.0f / (2.0f * 3.1415926535f)); - chassis.setTrackWidth(29.0f); + // 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) { diff --git a/examples/command_based/TankDriveDemo/TankDriveDemo.ino b/examples/command_based/TankDriveDemo/TankDriveDemo.ino index 581a18b..85135ac 100644 --- a/examples/command_based/TankDriveDemo/TankDriveDemo.ino +++ b/examples/command_based/TankDriveDemo/TankDriveDemo.ino @@ -34,8 +34,9 @@ void robotInit() { leftMotor.setBrakeMode(true); rightMotor.setBrakeMode(true); - chassis.setWheelRadius(31.4f / (2.0f * 3.1415926535f)); // cm cinsinden yaricap - chassis.setTrackWidth(28.0f); // cm + // 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); diff --git a/src/probot/command/examples/arm.hpp b/src/probot/command/examples/arm.hpp index f9095e8..4b8b06b 100644 --- a/src/probot/command/examples/arm.hpp +++ b/src/probot/command/examples/arm.hpp @@ -5,6 +5,8 @@ namespace probot::command::examples { + // NOTE: This mechanism example is disabled (not tested yet). +#if 0 struct IArm { virtual void setTargetAngleDeg(float degrees) = 0; virtual float getTargetAngleDeg() const = 0; @@ -71,5 +73,6 @@ namespace probot::command::examples { float max_angle_; bool has_limits_; }; +#endif } // namespace probot::command::examples diff --git a/src/probot/command/examples/elevator.hpp b/src/probot/command/examples/elevator.hpp index feffc7f..880c22d 100644 --- a/src/probot/command/examples/elevator.hpp +++ b/src/probot/command/examples/elevator.hpp @@ -5,6 +5,8 @@ namespace probot::command::examples { + // NOTE: This mechanism example is disabled (not tested yet). +#if 0 struct IElevator { virtual void setTargetHeight(float units) = 0; virtual float getTargetHeight() const = 0; @@ -73,5 +75,6 @@ namespace probot::command::examples { float max_height_; bool has_limits_; }; +#endif } // namespace probot::command::examples diff --git a/src/probot/command/examples/mecanum_drive.hpp b/src/probot/command/examples/mecanum_drive.hpp index 7c065db..37aa789 100644 --- a/src/probot/command/examples/mecanum_drive.hpp +++ b/src/probot/command/examples/mecanum_drive.hpp @@ -4,12 +4,16 @@ #include #include #include -#include #include +#if 0 +#include #include +#endif namespace probot::command::examples { +// NOTE: Closed-loop + odometry helpers are disabled (not tested yet). +#if 0 class MecanumDrive : public probot::command::SubsystemBase { public: enum class DriveMode { @@ -250,5 +254,71 @@ class MecanumDrive : public probot::command::SubsystemBase { probot::control::kinematics::MecanumDriveKinematics kinematics_; probot::control::odometry::MecanumDriveOdometry odometry_; }; +#endif + +class MecanumDrive : public probot::command::SubsystemBase { +public: + MecanumDrive(probot::motor::IMotorController* frontLeft, + probot::motor::IMotorController* frontRight, + probot::motor::IMotorController* rearLeft, + probot::motor::IMotorController* rearRight) + : probot::command::SubsystemBase("MecanumDrive"), + fl_(frontLeft), + fr_(frontRight), + rl_(rearLeft), + rr_(rearRight), + kinematics_(wheel_base_, track_width_) {} + + void setInverted(bool frontLeft, bool frontRight, bool rearLeft, bool rearRight){ + if (fl_) fl_->setInverted(frontLeft); + if (fr_) fr_->setInverted(frontRight); + if (rl_) rl_->setInverted(rearLeft); + if (rr_) rr_->setInverted(rearRight); + } + + void setTrackWidth(float width_units){ + track_width_ = width_units > 0.0f ? width_units : 1.0f; + kinematics_ = probot::control::kinematics::MecanumDriveKinematics(wheel_base_, track_width_); + } + + void setWheelBase(float base_units){ + wheel_base_ = base_units > 0.0f ? base_units : 1.0f; + kinematics_ = probot::control::kinematics::MecanumDriveKinematics(wheel_base_, track_width_); + } + + void drivePower(float vx, float vy, float omega){ + probot::control::ChassisSpeeds speeds(vx, vy, omega); + auto wheel = kinematics_.toWheelSpeeds(speeds); + float maxMag = std::max({std::fabs(wheel.frontLeft), std::fabs(wheel.frontRight), + std::fabs(wheel.rearLeft), std::fabs(wheel.rearRight), 1.0f}); + wheel.frontLeft /= maxMag; + wheel.frontRight /= maxMag; + wheel.rearLeft /= maxMag; + wheel.rearRight /= maxMag; + if (fl_) fl_->setPower(wheel.frontLeft); + if (fr_) fr_->setPower(wheel.frontRight); + if (rl_) rl_->setPower(wheel.rearLeft); + if (rr_) rr_->setPower(wheel.rearRight); + } + + void stop(){ drivePower(0.0f, 0.0f, 0.0f); } + + void periodic(uint32_t now_ms, uint32_t dt_ms) override { + if (fl_) fl_->update(now_ms, dt_ms); + if (fr_) fr_->update(now_ms, dt_ms); + if (rl_) rl_->update(now_ms, dt_ms); + if (rr_) rr_->update(now_ms, dt_ms); + } + +private: + probot::motor::IMotorController* fl_; + probot::motor::IMotorController* fr_; + probot::motor::IMotorController* rl_; + probot::motor::IMotorController* rr_; + + float track_width_ = 1.0f; + float wheel_base_ = 1.0f; + probot::control::kinematics::MecanumDriveKinematics kinematics_; +}; } // namespace probot::command::examples diff --git a/src/probot/command/examples/slider.hpp b/src/probot/command/examples/slider.hpp index 7e94c23..04fa250 100644 --- a/src/probot/command/examples/slider.hpp +++ b/src/probot/command/examples/slider.hpp @@ -4,6 +4,8 @@ #include namespace probot::command::examples { + // NOTE: This mechanism example is disabled (not tested yet). +#if 0 struct ISlider { virtual void setTargetLength(float length_units) = 0; // user units (e.g., cm) virtual float getTargetLength() const = 0; @@ -73,4 +75,5 @@ namespace probot::command::examples { float max_len_; bool has_limits_; }; +#endif } // namespace probot::command::examples diff --git a/src/probot/command/examples/tank_drive.hpp b/src/probot/command/examples/tank_drive.hpp index a8e7b71..afe0b1d 100644 --- a/src/probot/command/examples/tank_drive.hpp +++ b/src/probot/command/examples/tank_drive.hpp @@ -2,14 +2,18 @@ #include #include #include +#include +#if 0 #include #include #include -#include #include +#endif namespace probot::command::examples { +// NOTE: Closed-loop + odometry helpers are disabled (not tested yet). +#if 0 class TankDrive : public probot::command::SubsystemBase { public: enum class DriveMode { @@ -220,5 +224,44 @@ class TankDrive : public probot::command::SubsystemBase { float prev_left_pos_ = 0.0f; float prev_right_pos_ = 0.0f; }; +#endif + +class TankDrive : public probot::command::SubsystemBase { +public: + TankDrive(probot::motor::IMotorController* left, + probot::motor::IMotorController* right) + : probot::command::SubsystemBase("TankDrive"), + left_(left), + right_(right) {} + + void setInverted(bool left, bool right){ + if (left_) left_->setInverted(left); + if (right_) right_->setInverted(right); + } + + void drivePower(float left, float right){ + float l = clampUnit(left); + float r = clampUnit(right); + if (left_) left_->setPower(l); + if (right_) right_->setPower(r); + } + + void stop(){ drivePower(0.0f, 0.0f); } + + void periodic(uint32_t now_ms, uint32_t dt_ms) override { + if (left_) left_->update(now_ms, dt_ms); + if (right_) right_->update(now_ms, dt_ms); + } + +private: + static float clampUnit(float value){ + if (value > 1.0f) return 1.0f; + if (value < -1.0f) return -1.0f; + return value; + } + + probot::motor::IMotorController* left_; + probot::motor::IMotorController* right_; +}; } // namespace probot::command::examples diff --git a/src/probot/command/examples/telescopic_tube.hpp b/src/probot/command/examples/telescopic_tube.hpp index 28be9b2..61ed411 100644 --- a/src/probot/command/examples/telescopic_tube.hpp +++ b/src/probot/command/examples/telescopic_tube.hpp @@ -7,6 +7,8 @@ namespace probot::command::examples { + // NOTE: This mechanism example is disabled (not tested yet). +#if 0 struct ITelescopicTube { virtual void setTargetExtension(float units) = 0; virtual float getTargetExtension() const = 0; @@ -116,5 +118,6 @@ namespace probot::command::examples { probot::control::limiters::SlewRateLimiter slew_limiter_; bool limiter_initialized_; }; +#endif } // namespace probot::command::examples diff --git a/src/probot/command/examples/turret.hpp b/src/probot/command/examples/turret.hpp index ada5c74..c9e3098 100644 --- a/src/probot/command/examples/turret.hpp +++ b/src/probot/command/examples/turret.hpp @@ -7,6 +7,8 @@ namespace probot::command::examples { + // NOTE: This mechanism example is disabled (not tested yet). +#if 0 struct ITurret { virtual void setTargetAngleDeg(float degrees) = 0; virtual float getTargetAngleDeg() const = 0; @@ -119,5 +121,6 @@ namespace probot::command::examples { probot::control::limiters::SlewRateLimiter slew_limiter_; bool limiter_initialized_; }; +#endif } // namespace probot::command::examples diff --git a/src/probot/command/scheduler.hpp b/src/probot/command/scheduler.hpp index e8f0991..bbb7fa3 100644 --- a/src/probot/command/scheduler.hpp +++ b/src/probot/command/scheduler.hpp @@ -8,6 +8,12 @@ #include #include +#ifndef PROBOT_COMMAND_WARNING_SHOWN +#define PROBOT_COMMAND_WARNING_SHOWN +#pragma message("WARNING: Command-based system tests are not complete; use with caution.") +#pragma message("UYARI: Command-based sistem testleri tamamlanmadi; kullanirken dikkatli olun.") +#endif + #ifdef ESP32 #include #include @@ -140,6 +146,12 @@ class Scheduler { if (!queue_) { queue_ = xQueueCreate(kQueueSize, sizeof(Request)); } + static bool warned = false; + if (!warned) { + warned = true; + Serial.println("[WARN] Command-based system tests are not complete; use with caution."); + Serial.println("[UYARI] Command-based sistem testleri tamamlanmadi; kullanirken dikkatli olun."); + } } private: diff --git a/tests/test_chassis.cpp b/tests/test_chassis.cpp index a1e13f0..74a3540 100644 --- a/tests/test_chassis.cpp +++ b/tests/test_chassis.cpp @@ -43,6 +43,8 @@ TEST_CASE(tank_drive_power_clamp_and_invert){ EXPECT_NEAR(right.lastPower, 0.5f, 1e-5f); } +// NOTE: Closed-loop/odometry chassis tests are disabled (not tested yet). +#if 0 TEST_CASE(tank_drive_velocity_normalized){ MotorStub left, right; left.velSupported = true; @@ -89,6 +91,7 @@ TEST_CASE(tank_drive_odometry_updates_pose){ EXPECT_NEAR(tank.pose().x, 2.0f * 3.1415926535f, 1e-4f); EXPECT_NEAR(tank.pose().y, 0.0f, 1e-4f); } +#endif TEST_CASE(mecanum_drive_power_normalizes_outputs){ MotorStub fl, fr, rl, rr; @@ -115,6 +118,7 @@ TEST_CASE(mecanum_drive_power_normalizes_outputs){ EXPECT_NEAR(rr.lastPower, -raw_rr, 1e-5f); } +#if 0 TEST_CASE(mecanum_drive_velocity_uses_controller){ MotorStub fl, fr, rl, rr; fl.velSupported = true; @@ -145,3 +149,4 @@ TEST_CASE(mecanum_drive_velocity_status_unsupported){ EXPECT_TRUE(mech.lastStatus() == probot::command::examples::MecanumDrive::CommandStatus::kVelocityUnsupported); } +#endif diff --git a/tests/test_mechanisms.cpp b/tests/test_mechanisms.cpp index 94ad6c3..6e3fb86 100644 --- a/tests/test_mechanisms.cpp +++ b/tests/test_mechanisms.cpp @@ -1,3 +1,5 @@ +// NOTE: Mechanism examples are disabled (not tested yet). +#if 0 #include "test_harness.hpp" #include @@ -95,3 +97,4 @@ TEST_CASE(telescopic_stage_limits){ tube.periodic(0, 0); EXPECT_NEAR(harness.motor.lastSetpoint(), 120.0f * 80.0f, 1e-5f); } +#endif From 4bef91a5dc39fab17334e1ecdb2ef836a47e894d Mon Sep 17 00:00:00 2001 From: tunapro Date: Fri, 2 Jan 2026 09:27:06 +0300 Subject: [PATCH 12/14] telemetry --- .../esp32s3/driver_station_esp32.hpp | 5 ++ src/driverstation/esp32s3/index_html.h | 22 ++++++ src/probot.h | 1 + src/probot/command/scheduler.hpp | 36 ++++++--- src/probot/telemetry/telemetry.hpp | 73 +++++++++++++++++++ 5 files changed, 125 insertions(+), 12 deletions(-) create mode 100644 src/probot/telemetry/telemetry.hpp diff --git a/src/driverstation/esp32s3/driver_station_esp32.hpp b/src/driverstation/esp32s3/driver_station_esp32.hpp index d1ee557..c9441a7 100644 --- a/src/driverstation/esp32s3/driver_station_esp32.hpp +++ b/src/driverstation/esp32s3/driver_station_esp32.hpp @@ -5,6 +5,7 @@ #include #include #include +#include #include "index_html.h" #ifndef PROBOT_WIFI_AP_PASSWORD @@ -38,6 +39,7 @@ namespace probot::driverstation::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("/telemetry", HTTP_GET, [this](){ if (!enforceOwner()) return; handleTelemetry(); }); _server.begin(); } @@ -151,6 +153,9 @@ namespace probot::driverstation::esp32 { _server.send(200, "text/plain", "OK"); } + void handleTelemetry(){ + _server.send(200, "text/plain", probot::telemetry::getBuffer()); + } robot::StateService& _rs; io::GamepadService& _gs; diff --git a/src/driverstation/esp32s3/index_html.h b/src/driverstation/esp32s3/index_html.h index 25c4c19..4dae8b7 100644 --- a/src/driverstation/esp32s3/index_html.h +++ b/src/driverstation/esp32s3/index_html.h @@ -710,6 +710,11 @@ const char MAIN_page[] PROGMEM = R"=====(
No axis data...
No button data...
+
+

Telemetry

+

+      
+    
diff --git a/src/probot.h b/src/probot.h index 259a53e..93c4185 100644 --- a/src/probot.h +++ b/src/probot.h @@ -12,6 +12,7 @@ #include #include #include +#include // Optional modules (explicit include): // - (command + subsystem) diff --git a/src/probot/command/scheduler.hpp b/src/probot/command/scheduler.hpp index bbb7fa3..4ea0660 100644 --- a/src/probot/command/scheduler.hpp +++ b/src/probot/command/scheduler.hpp @@ -286,9 +286,20 @@ class Scheduler { } // Try to schedule a command (conflict resolution) + // WPILib behavior: reject commands that don't run when disabled void tryScheduleCommand(ICommand* cmd) { if (!cmd) return; + // WPILib: Don't schedule if robot is disabled and command doesn't run when disabled + auto snap = probot::robot::state().read(); + bool is_disabled = (snap.status == probot::robot::Status::STOP); + if (is_disabled && !cmd->runsWhenDisabled()) { +#ifndef PROBOT_SCHED_NOLOG + Serial.printf("[SCHED] rejected (disabled): %s\n", cmd->name()); +#endif + return; + } + // Already scheduled? if (findCommandSlot(cmd) >= 0) { #ifndef PROBOT_SCHED_NOLOG @@ -433,13 +444,15 @@ class Scheduler { } // Run all scheduled commands - void runCommands(uint32_t now, bool allow_updates) { + // WPILib behavior: commands without runsWhenDisabled() are CANCELLED when disabled + void runCommands(uint32_t now, bool is_enabled) { for (size_t i = 0; i < kMaxCommands; ++i) { auto& slot = commands_[i]; if (slot.state == CommandState::kNone || !slot.cmd) continue; - // Check runsWhenDisabled - if (!allow_updates && !slot.cmd->runsWhenDisabled()) { + // WPILib: Cancel commands that don't run when disabled + if (!is_enabled && !slot.cmd->runsWhenDisabled()) { + cancelCommand(static_cast(i), true); continue; } @@ -543,7 +556,7 @@ class Scheduler { // Read robot state auto snap = probot::robot::state().read(); - bool allow_updates = (snap.status != probot::robot::Status::STOP); + bool is_enabled = (snap.status != probot::robot::Status::STOP); // Handle state transitions handleTransitions(snap.status, snap.phase); @@ -551,16 +564,15 @@ class Scheduler { // Process queue requests processRequests(); - if (allow_updates) { - // Run subsystems - runSubsystems(now, dt); - } + // WPILib behavior: Subsystem periodic() ALWAYS runs (even when disabled) + // This allows sensor reading, odometry updates, etc. during disabled + runSubsystems(now, dt); - // Run commands - runCommands(now, allow_updates); + // Run commands (disabled commands are cancelled inside runCommands) + runCommands(now, is_enabled); - // Schedule default commands for idle subsystems - if (allow_updates) { + // Schedule default commands only when enabled + if (is_enabled) { scheduleDefaultCommands(); } diff --git a/src/probot/telemetry/telemetry.hpp b/src/probot/telemetry/telemetry.hpp new file mode 100644 index 0000000..2edbdfb --- /dev/null +++ b/src/probot/telemetry/telemetry.hpp @@ -0,0 +1,73 @@ +#pragma once +#include +#include +#include +#include + +namespace probot::telemetry { + +namespace detail { + constexpr size_t BUFFER_SIZE = 256; + + struct TelemetryBuffer { + char data[BUFFER_SIZE]; + volatile uint16_t len = 0; + volatile uint32_t seq = 0; + }; + + inline TelemetryBuffer g_buffer{}; +} + +inline void print(const char* msg) { + auto& buf = detail::g_buffer; + size_t msgLen = strlen(msg); + size_t space = detail::BUFFER_SIZE - 1 - buf.len; + + if (msgLen > space) { + // Buffer dolu, baştan yaz + buf.len = 0; + space = detail::BUFFER_SIZE - 1; + } + + size_t toWrite = (msgLen < space) ? msgLen : space; + memcpy(buf.data + buf.len, msg, toWrite); + uint16_t oldLen = buf.len; buf.len = static_cast(oldLen + toWrite); + buf.data[buf.len] = '\0'; + uint32_t s = buf.seq; buf.seq = s + 1; +} + +inline void println(const char* msg = "") { + print(msg); + print("\n"); +} + +inline void printf(const char* fmt, ...) { + char tmp[128]; + va_list args; + va_start(args, fmt); + vsnprintf(tmp, sizeof(tmp), fmt, args); + va_end(args); + print(tmp); +} + +inline void clear() { + auto& buf = detail::g_buffer; + buf.len = 0; + buf.data[0] = '\0'; + uint32_t s = buf.seq; buf.seq = s + 1; +} + +// Internal: DS tarafından çağrılır +inline const char* getBuffer() { + return detail::g_buffer.data; +} + +inline uint16_t getLength() { + return detail::g_buffer.len; +} + +inline uint32_t getSeq() { + return detail::g_buffer.seq; +} + +} // namespace probot::telemetry From 4d77a4e309b171909c35fb1fe3f504feaf233831 Mon Sep 17 00:00:00 2001 From: tunapro Date: Fri, 2 Jan 2026 09:27:13 +0300 Subject: [PATCH 13/14] edit examples --- Makefile | 2 +- examples/IBT2MotorDemo/IBT2MotorDemo.ino | 152 +++++++++++++ examples/JoystickTest/JoystickTest.ino | 215 +++++++++++++++--- .../MotorControllerDemo.ino | 119 ---------- .../MotorOpenLoopDemo/MotorOpenLoopDemo.ino | 125 ++++++++-- examples/ShooterDemo/ShooterDemo.ino | 67 ------ examples/SliderDemo/SliderDemo.ino | 77 ------- examples/TurretDemo/TurretDemo.ino | 77 ------- .../command_based/ShooterDemo/ShooterDemo.ino | 84 +++++++ .../command_based/SliderDemo/SliderDemo.ino | 83 +++++++ .../command_based/TurretDemo/TurretDemo.ino | 81 +++++++ src/driverstation/esp32s3/index_html.h | 10 +- 12 files changed, 691 insertions(+), 401 deletions(-) create mode 100644 examples/IBT2MotorDemo/IBT2MotorDemo.ino delete mode 100644 examples/MotorControllerDemo/MotorControllerDemo.ino delete mode 100644 examples/ShooterDemo/ShooterDemo.ino delete mode 100644 examples/SliderDemo/SliderDemo.ino delete mode 100644 examples/TurretDemo/TurretDemo.ino create mode 100644 examples/command_based/ShooterDemo/ShooterDemo.ino create mode 100644 examples/command_based/SliderDemo/SliderDemo.ino create mode 100644 examples/command_based/TurretDemo/TurretDemo.ino diff --git a/Makefile b/Makefile index e99c80c..4b64a7b 100644 --- a/Makefile +++ b/Makefile @@ -12,7 +12,7 @@ VERSION_SYNC_SCRIPT := $(CURDIR)/tools/sync_version.py # Examples EXAMPLES_DIR := $(CURDIR)/examples -EXAMPLE_SKETCHES := $(shell find $(EXAMPLES_DIR) -maxdepth 2 -mindepth 1 -name "*.ino") +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)) 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 955c0ff..3b07e14 100644 --- a/examples/JoystickTest/JoystickTest.ino +++ b/examples/JoystickTest/JoystickTest.ino @@ -1,65 +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 - -// 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::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); - // Kart ve motor kontrolcusunu hazirla. - motor.begin(); - motor.setBrakeMode(true); // boşta tam fren uygula - motor.setPower(0.0f); - - 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() { - motor.setPower(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(); - - // Okuduğumuz değeri doğrudan motora gönderiyoruz. - motor.setPower(axis); - - // Seri log ile joystick verisini ve motor komutunu gözlemleyin. - Serial.printf("[JoystickTest] seq=%lu axisY=%.2f motorCmd=%.2f\n", + // ========================================================================= + // 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()), - axis, - motor.getPower()); - - delay(50); + 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()); + + // ========================================================================= + // 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ı + + // 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()); + + // 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"); - motor.setPower(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. - delay(20); + delay(100); } diff --git a/examples/MotorControllerDemo/MotorControllerDemo.ino b/examples/MotorControllerDemo/MotorControllerDemo.ino deleted file mode 100644 index 8dad660..0000000 --- a/examples/MotorControllerDemo/MotorControllerDemo.ino +++ /dev/null @@ -1,119 +0,0 @@ -#define PROBOT_WIFI_AP_PASSWORD "ProBot1234" - -#include -#include -#include -#include - -// Kullanilan Boardoza VNH motor kontrolcusu pinleri (kendi kartiniza gore guncelleyin). -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::BoardozaVNH5019MotorController motor(PIN_INA, PIN_INB, PIN_PWM, PIN_ENA, PIN_ENB); -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::sensors::IEncoder* encoder = nullptr; - - -static probot::control::ControlType g_mode = probot::control::ControlType::kVelocity; -static bool g_has_encoder = false; - -void robotInit() { - Serial.begin(115200); - delay(100); - - motor.begin(); - motor.setBrakeMode(true); - - motor.setTimeoutMs(0); // joystick bırakıldığında çıkış sıfırlanmasın - if (encoder) { - motor.attachEncoder(encoder); - motor.setVelocityPidConfig(kVelocityPid); - motor.setVelocity(0.0f); - g_has_encoder = true; - } else { - g_mode = probot::control::ControlType::kPercent; - g_has_encoder = false; - } - - Serial.println("[IMotorControllerDemo] robotInit: Kapalı çevrim denemesi için hazır"); - if (!g_has_encoder) { - Serial.println("[IMotorControllerDemo] Encoder yok, sadece yüzde modunda çalışır"); - } -} - -void robotEnd() { - motor.setPower(0.0f); - Serial.println("[IMotorControllerDemo] robotEnd: Motor kapatıldı"); -} - -void teleopInit() { - Serial.println("[IMotorControllerDemo] teleopInit:" - " sol eksen referans, A butonu mod değiştirir (encoder varsa velocity)"); -} - -void teleopLoop() { - auto js = probot::io::joystick_api::makeDefault(); - - if (js.getRawButton(0)) { - if (g_has_encoder) { - g_mode = (g_mode == probot::control::ControlType::kVelocity) - ? probot::control::ControlType::kPercent - : probot::control::ControlType::kVelocity; - } else { - g_mode = probot::control::ControlType::kPercent; - } - if (g_mode == probot::control::ControlType::kVelocity) { - motor.setVelocity(0.0f); - } else { - motor.setPower(0.0f); - } - Serial.printf("[IMotorControllerDemo] 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); - if (g_mode == probot::control::ControlType::kVelocity) { - motor.setVelocity(target); - } else { - motor.setPower(target); - } - motor.update(millis(), 20); - - Serial.printf("[IMotorControllerDemo] mode=%s target=%.2f measurement=%.2f out=%.2f\n", - g_mode == probot::control::ControlType::kVelocity ? "VEL" : "PCT", - target, - motor.lastMeasurement(), - motor.lastOutput()); - - delay(20); -} - -static uint32_t g_auto_start = 0; - -void autonomousInit() { - Serial.println("[IMotorControllerDemo] autonomousInit: 2 saniyelik hız profili"); - g_auto_start = millis(); - if (g_has_encoder) { - motor.setVelocity(80.0f); - } else { - motor.setPower(0.6f); - } -} - -void autonomousLoop() { - motor.update(millis(), 20); - if (millis() - g_auto_start > 2000) { - if (g_has_encoder) { - motor.setVelocity(0.0f); - } else { - motor.setPower(0.0f); - } - } - delay(20); -} diff --git a/examples/MotorOpenLoopDemo/MotorOpenLoopDemo.ino b/examples/MotorOpenLoopDemo/MotorOpenLoopDemo.ino index 094a808..7af948a 100644 --- a/examples/MotorOpenLoopDemo/MotorOpenLoopDemo.ino +++ b/examples/MotorOpenLoopDemo/MotorOpenLoopDemo.ino @@ -1,62 +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 -// Boardoza VNH motor kontrolcusunu kullanirken 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; - +// ============================================================================ +// 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(); - motor.setBrakeMode(false); // kontrolcu serbest birakildi, coast modunda + + // 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] robotInit: IMotorController arayuzunu test etmek icin hazir"); + 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] robotEnd: Motor durduruldu"); + Serial.println("[MotorOpenLoopDemo] Motor durduruldu"); } +/** + * Teleop modu başladığında çağrılır + */ void teleopInit() { - Serial.println("[MotorOpenLoopDemo] teleopInit:" - " sol eksen gücü, sağ tetik ise yön tersleme yapar"); + 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 çubuktan ham güç, sağ tetikten tersleme isteği okuyoruz. + // 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(); - bool invert = js.getRightTriggerAxis() > 0.5f; + // 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); - Serial.printf("[MotorOpenLoopDemo] power=%.2f invert=%d motorOut=%.2f\n", + // Debug çıktısı + Serial.printf("[Motor] güç=%.2f ters=%d çıkış=%.2f\n", power, invert ? 1 : 0, motor.getPower()); - delay(40); + // 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] autonomousInit: Motoru yavasca durduruyoruz"); + 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 e1fc47c..0000000 --- a/examples/ShooterDemo/ShooterDemo.ino +++ /dev/null @@ -1,67 +0,0 @@ -#define PROBOT_WIFI_AP_PASSWORD "ProBot1234" - -#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::BoardozaVNH5019MotorController motor(PIN_INA, PIN_INB, PIN_PWM, PIN_ENA, PIN_ENB); - - -void robotInit() { - Serial.begin(115200); - delay(100); - - motor.begin(); - motor.setBrakeMode(false); // shooter çarkında coast tercihi yapılabilir - motor.setPower(0.0f); - - Serial.println("[ShooterDemo] robotInit: Shooter kontrolü başlatıldı"); -} - -void robotEnd() { - motor.setPower(0.0f); - 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 power = accel; // 0..1 açık çevrim güç - if (brake > 0.2f) power = 0.0f; // fren tetiklendiğinde durdur - - motor.setPower(power); - - Serial.printf("[ShooterDemo] power=%.2f out=%.2f\n", - power, - motor.getPower()); - - delay(20); -} - -void autonomousInit() { - Serial.println("[ShooterDemo] autonomousInit: 2 saniye spool, sonra durdur"); - motor.setPower(0.8f); -} - -void autonomousLoop() { - static uint32_t start = millis(); - if (millis() - start > 2000) { - motor.setPower(0.0f); - } - delay(20); -} diff --git a/examples/SliderDemo/SliderDemo.ino b/examples/SliderDemo/SliderDemo.ino deleted file mode 100644 index ea24a1c..0000000 --- a/examples/SliderDemo/SliderDemo.ino +++ /dev/null @@ -1,77 +0,0 @@ -#define PROBOT_WIFI_AP_PASSWORD "ProBot1234" - -#include -#include -#include - -// Slider mekanizmasi icin kullanilan VNH motor kontrolcusu 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::BoardozaVNH5019MotorController motor(PIN_INA, PIN_INB, PIN_PWM, PIN_ENA, PIN_ENB); - - -void robotInit() { - Serial.begin(115200); - delay(100); - - motor.begin(); - motor.setBrakeMode(true); - motor.setPower(0.0f); - - Serial.println("[SliderDemo] robotInit: Slider kontrolü hazır"); -} - -void robotEnd() { - motor.setPower(0.0f); - Serial.println("[SliderDemo] robotEnd: Motor sıfırlandı"); -} - -void teleopInit() { - Serial.println("[SliderDemo] teleopInit:" - " D-pad yukarı/aşağı slider gücü gönderir"); -} - -void teleopLoop() { - auto js = probot::io::joystick_api::makeDefault(); - int pov = js.getPOV(); - - float cmd = 0.0f; - if (pov == 0) cmd = 0.6f; // yukarı - if (pov == 180) cmd = -0.6f; // aşağı - motor.setPower(cmd); - - Serial.printf("[SliderDemo] cmd=%.2f out=%.2f\n", - cmd, - motor.getPower()); - - 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) { - motor.setPower(0.6f); - stateStart = now; - state = 1; - } else if (state == 1 && now - stateStart > 1200) { - motor.setPower(-0.6f); - stateStart = now; - state = 2; - } else if (state == 2 && now - stateStart > 1200) { - motor.setPower(0.0f); - state = 3; - } - - delay(20); -} diff --git a/examples/TurretDemo/TurretDemo.ino b/examples/TurretDemo/TurretDemo.ino deleted file mode 100644 index 6643380..0000000 --- a/examples/TurretDemo/TurretDemo.ino +++ /dev/null @@ -1,77 +0,0 @@ -#define PROBOT_WIFI_AP_PASSWORD "ProBot1234" - -#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::BoardozaVNH5019MotorController motor(PIN_INA, PIN_INB, PIN_PWM, PIN_ENA, PIN_ENB); - - -void robotInit() { - Serial.begin(115200); - delay(100); - - motor.begin(); - motor.setBrakeMode(true); - motor.setPower(0.0f); - - Serial.println("[TurretDemo] robotInit: Taret kontrolü hazır"); -} - -void robotEnd() { - motor.setPower(0.0f); - Serial.println("[TurretDemo] robotEnd: Taret durduruldu"); -} - -void teleopInit() { - Serial.println("[TurretDemo] teleopInit:" - " sağ çubuk X taret gücünü belirler, B butonu durdurur"); -} - -void teleopLoop() { - auto js = probot::io::joystick_api::makeDefault(); - - float cmd = js.getRightX(); // -1..1 - if (js.getRawButton(1)) { // B butonu - cmd = 0.0f; - } - motor.setPower(cmd); - - Serial.printf("[TurretDemo] cmd=%.2f out=%.2f\n", - cmd, - motor.getPower()); - - 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) { - motor.setPower(-0.4f); - stateStart = now; - state = 1; - } else if (state == 1 && now - stateStart > 1200) { - motor.setPower(0.4f); - stateStart = now; - state = 2; - } else if (state == 2 && now - stateStart > 1200) { - motor.setPower(0.0f); - state = 3; - } - - 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/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/src/driverstation/esp32s3/index_html.h b/src/driverstation/esp32s3/index_html.h index 4dae8b7..62d4779 100644 --- a/src/driverstation/esp32s3/index_html.h +++ b/src/driverstation/esp32s3/index_html.h @@ -701,6 +701,11 @@ const char MAIN_page[] PROGMEM = R"=====(
+
+

Telemetry

+

+      
+    

System Logs