From 5997eb22b83111a0047744c3b846cad8e626add9 Mon Sep 17 00:00:00 2001 From: tunapro Date: Thu, 16 Oct 2025 13:39:07 +0300 Subject: [PATCH 01/26] Simplify motor driver API and remove ownership handling --- .../AdvancedMecanumDrive.ino | 6 +-- .../AdvancedTankDrive/AdvancedTankDrive.ino | 6 +-- .../chassis/nfr_advanced_mecanum_drive.hpp | 27 ++++------ .../chassis/nfr_advanced_tank_drive.hpp | 21 ++------ src/probot/chassis/simple_mecanum.hpp | 26 ++------- src/probot/chassis/simple_tank.hpp | 20 ++----- src/probot/control/closed_loop_motor.hpp | 35 +++--------- .../control/closed_loop_motor_group.hpp | 26 ++------- .../devices/motors/boardoza_ba6208_driver.cpp | 15 +----- .../devices/motors/boardoza_ba6208_driver.hpp | 7 +-- .../motors/boardoza_vnh_motor_driver.cpp | 16 +----- .../motors/boardoza_vnh_motor_driver.hpp | 7 +-- src/probot/devices/motors/imotor_driver.hpp | 9 +--- src/probot/devices/motors/motor_group.hpp | 30 ++--------- src/probot/devices/motors/motor_handle.hpp | 10 +--- src/probot/test/test_motor.hpp | 18 +++---- tests/test_chassis.cpp | 25 +-------- tests/test_closed_loop.cpp | 53 ++----------------- tests/test_devices.cpp | 35 +++++------- tests/test_mechanisms.cpp | 6 +-- 20 files changed, 74 insertions(+), 324 deletions(-) diff --git a/examples/nfr/AdvancedMecanumDrive/AdvancedMecanumDrive.ino b/examples/nfr/AdvancedMecanumDrive/AdvancedMecanumDrive.ino index f80ce5b..078b0dc 100644 --- a/examples/nfr/AdvancedMecanumDrive/AdvancedMecanumDrive.ino +++ b/examples/nfr/AdvancedMecanumDrive/AdvancedMecanumDrive.ino @@ -10,11 +10,7 @@ static probot::motor::MotorHandle flHandle(flHW), frHandle(frHW), rlHandle(rlHW) class NullMotorController : public probot::control::IMotorController { public: explicit NullMotorController(probot::motor::MotorHandle& handle) : handle_(handle) {} - bool claim(void* owner) override { return handle_.underlying().claim(owner); } - void release(void* owner) override { handle_.underlying().release(owner); } - bool setPower(float power, void* owner) override { return handle_.underlying().setPower(power, owner); } - bool isClaimed() const override { return handle_.underlying().isClaimed(); } - void* currentOwner() const override { return handle_.underlying().currentOwner(); } + bool setPower(float power) override { return handle_.underlying().setPower(power); } void setInverted(bool inv) override { handle_.setInverted(inv); } bool getInverted() const override { return handle_.getInverted(); } void setSetpoint(float, probot::controllers::ControlType, int) override {} diff --git a/examples/nfr/AdvancedTankDrive/AdvancedTankDrive.ino b/examples/nfr/AdvancedTankDrive/AdvancedTankDrive.ino index 2a83069..d229b92 100644 --- a/examples/nfr/AdvancedTankDrive/AdvancedTankDrive.ino +++ b/examples/nfr/AdvancedTankDrive/AdvancedTankDrive.ino @@ -19,11 +19,7 @@ static probot::control::PID pidRight({0.4f,0.0f,0.0f,-1.0f,1.0f}); // Null controllers stand in for real motor controllers – swap with real ones on hardware. class NullMotorController : public probot::control::IMotorController { public: - bool claim(void* owner) override { return handle_.underlying().claim(owner); } - void release(void* owner) override { handle_.underlying().release(owner); } - bool setPower(float power, void* owner) override { return handle_.underlying().setPower(power, owner); } - bool isClaimed() const override { return handle_.underlying().isClaimed(); } - void* currentOwner() const override { return handle_.underlying().currentOwner(); } + bool setPower(float power) override { return handle_.underlying().setPower(power); } void setInverted(bool inv) override { handle_.setInverted(inv); } bool getInverted() const override { return handle_.getInverted(); } diff --git a/src/probot/chassis/nfr_advanced_mecanum_drive.hpp b/src/probot/chassis/nfr_advanced_mecanum_drive.hpp index 13cd10a..657ef15 100644 --- a/src/probot/chassis/nfr_advanced_mecanum_drive.hpp +++ b/src/probot/chassis/nfr_advanced_mecanum_drive.hpp @@ -53,19 +53,14 @@ namespace probot::chassis { limiterVx_(config.slewRateVx, 0.0f), limiterVy_(config.slewRateVy, 0.0f) { - if (fl_) { fl_->claim(&tokenFL_); applyWheelMotionProfile(fl_); } - if (fr_) { fr_->claim(&tokenFR_); applyWheelMotionProfile(fr_); } - if (rl_) { rl_->claim(&tokenRL_); applyWheelMotionProfile(rl_); } - if (rr_) { rr_->claim(&tokenRR_); applyWheelMotionProfile(rr_); } + applyWheelMotionProfile(fl_); + applyWheelMotionProfile(fr_); + applyWheelMotionProfile(rl_); + applyWheelMotionProfile(rr_); controller_.setEnabled(true); } - ~NfrAdvancedMecanumDrive(){ - if (fl_) fl_->release(&tokenFL_); - if (fr_) fr_->release(&tokenFR_); - if (rl_) rl_->release(&tokenRL_); - if (rr_) rr_->release(&tokenRR_); - } + ~NfrAdvancedMecanumDrive() = default; void setImu(probot::sensors::imu::IImu* imu){ imu_ = imu; } probot::sensors::imu::IImu* imu() const { return imu_; } @@ -206,10 +201,10 @@ namespace probot::chassis { for (float o : outputs) maxMag = std::max(maxMag, std::fabs(o)); float scale = (maxMag > config_.maxOutput) ? config_.maxOutput / maxMag : 1.0f; - if (fl_) fl_->setPower(std::clamp(outputs[0] * scale / config_.maxOutput, -1.0f, 1.0f), &tokenFL_); - if (fr_) fr_->setPower(std::clamp(outputs[1] * scale / config_.maxOutput, -1.0f, 1.0f), &tokenFR_); - if (rl_) rl_->setPower(std::clamp(outputs[2] * scale / config_.maxOutput, -1.0f, 1.0f), &tokenRL_); - if (rr_) rr_->setPower(std::clamp(outputs[3] * scale / config_.maxOutput, -1.0f, 1.0f), &tokenRR_); + if (fl_) fl_->setPower(std::clamp(outputs[0] * scale / config_.maxOutput, -1.0f, 1.0f)); + if (fr_) fr_->setPower(std::clamp(outputs[1] * scale / config_.maxOutput, -1.0f, 1.0f)); + if (rl_) rl_->setPower(std::clamp(outputs[2] * scale / config_.maxOutput, -1.0f, 1.0f)); + if (rr_) rr_->setPower(std::clamp(outputs[3] * scale / config_.maxOutput, -1.0f, 1.0f)); } prevWheelTargets_ = wheelTargets; @@ -232,10 +227,6 @@ namespace probot::chassis { probot::control::IMotorController* fr_; probot::control::IMotorController* rl_; probot::control::IMotorController* rr_; - void* tokenFL_ = reinterpret_cast(reinterpret_cast(this) + 0); - void* tokenFR_ = reinterpret_cast(reinterpret_cast(this) + 1); - void* tokenRL_ = reinterpret_cast(reinterpret_cast(this) + 2); - void* tokenRR_ = reinterpret_cast(reinterpret_cast(this) + 3); Config config_; probot::control::kinematics::MecanumDriveKinematics kinematics_; diff --git a/src/probot/chassis/nfr_advanced_tank_drive.hpp b/src/probot/chassis/nfr_advanced_tank_drive.hpp index 1f70d6d..9921416 100644 --- a/src/probot/chassis/nfr_advanced_tank_drive.hpp +++ b/src/probot/chassis/nfr_advanced_tank_drive.hpp @@ -42,20 +42,11 @@ namespace probot::chassis { pidLeft_(config.velocityPid), pidRight_(config.velocityPid), feedforward_(config.feedforward) { - if (left_) { - left_->claim(&tokenLeft_); - applyWheelMotionProfile(left_); - } - if (right_) { - right_->claim(&tokenRight_); - applyWheelMotionProfile(right_); - } + applyWheelMotionProfile(left_); + applyWheelMotionProfile(right_); } - ~NfrAdvancedTankDrive(){ - if (left_) left_->release(&tokenLeft_); - if (right_) right_->release(&tokenRight_); - } + ~NfrAdvancedTankDrive() = default; void setImu(probot::sensors::imu::IImu* imu){ imu_ = imu; } probot::sensors::imu::IImu* imu() const { return imu_; } @@ -192,8 +183,8 @@ namespace probot::chassis { float leftPower = std::clamp(leftOutput * scale / config_.maxOutput, -1.0f, 1.0f); float rightPower = std::clamp(rightOutput * scale / config_.maxOutput, -1.0f, 1.0f); - if (left_) left_->setPower(leftPower, &tokenLeft_); - if (right_) right_->setPower(rightPower, &tokenRight_); + if (left_) left_->setPower(leftPower); + if (right_) right_->setPower(rightPower); } prevLeftTarget_ = leftTarget; @@ -206,8 +197,6 @@ namespace probot::chassis { private: probot::control::IMotorController* left_; probot::control::IMotorController* right_; - void* tokenLeft_ = this; - void* tokenRight_ = reinterpret_cast(reinterpret_cast(this) + 1); Config config_; probot::control::kinematics::DifferentialDriveKinematics kinematics_; diff --git a/src/probot/chassis/simple_mecanum.hpp b/src/probot/chassis/simple_mecanum.hpp index 85cbc82..33b38fe 100644 --- a/src/probot/chassis/simple_mecanum.hpp +++ b/src/probot/chassis/simple_mecanum.hpp @@ -13,19 +13,7 @@ namespace probot::chassis { probot::motor::IMotorDriver* frontRight, probot::motor::IMotorDriver* rearLeft, probot::motor::IMotorDriver* rearRight) - : fl_(frontLeft), fr_(frontRight), rl_(rearLeft), rr_(rearRight) { - if (fl_) fl_->claim(&tokenFL_); - if (fr_) fr_->claim(&tokenFR_); - if (rl_) rl_->claim(&tokenRL_); - if (rr_) rr_->claim(&tokenRR_); - } - - ~SimpleMecanumDrive(){ - if (fl_) fl_->release(&tokenFL_); - if (fr_) fr_->release(&tokenFR_); - if (rl_) rl_->release(&tokenRL_); - if (rr_) rr_->release(&tokenRR_); - } + : fl_(frontLeft), fr_(frontRight), rl_(rearLeft), rr_(rearRight) {} void setInverted(bool frontLeft, bool frontRight, bool rearLeft, bool rearRight){ if (fl_) fl_->setInverted(frontLeft); @@ -41,10 +29,10 @@ namespace probot::chassis { float rr = vx - vy + omega; float maxMag = std::max({std::fabs(fl), std::fabs(fr), std::fabs(rl), std::fabs(rr), 1.0f}); fl /= maxMag; fr /= maxMag; rl /= maxMag; rr /= maxMag; - if (fl_) fl_->setPower(fl, &tokenFL_); - if (fr_) fr_->setPower(fr, &tokenFR_); - if (rl_) rl_->setPower(rl, &tokenRL_); - if (rr_) rr_->setPower(rr, &tokenRR_); + if (fl_) fl_->setPower(fl); + if (fr_) fr_->setPower(fr); + if (rl_) rl_->setPower(rl); + if (rr_) rr_->setPower(rr); } void stop(){ driveCartesian(0.0f, 0.0f, 0.0f); } @@ -54,9 +42,5 @@ namespace probot::chassis { probot::motor::IMotorDriver* fr_; probot::motor::IMotorDriver* rl_; probot::motor::IMotorDriver* rr_; - void* tokenFL_ = this; - void* tokenFR_ = reinterpret_cast(reinterpret_cast(this) + 1); - void* tokenRL_ = reinterpret_cast(reinterpret_cast(this) + 2); - void* tokenRR_ = reinterpret_cast(reinterpret_cast(this) + 3); }; } diff --git a/src/probot/chassis/simple_tank.hpp b/src/probot/chassis/simple_tank.hpp index aca7900..770459b 100644 --- a/src/probot/chassis/simple_tank.hpp +++ b/src/probot/chassis/simple_tank.hpp @@ -10,15 +10,7 @@ namespace probot::chassis { class SimpleTankDrive { public: SimpleTankDrive(probot::motor::IMotorDriver* left, probot::motor::IMotorDriver* right) - : left_(left), right_(right), ownerLeft_(this), ownerRight_(reinterpret_cast(reinterpret_cast(this)+1)) { - if (left_) left_->claim(ownerLeft_); - if (right_) right_->claim(ownerRight_); - } - - ~SimpleTankDrive(){ - if (left_) left_->release(ownerLeft_); - if (right_) right_->release(ownerRight_); - } + : left_(left), right_(right) {} void setInverted(bool left, bool right){ if (left_) left_->setInverted(left); @@ -28,19 +20,17 @@ namespace probot::chassis { void drive(float leftPower, float rightPower){ leftPower = std::clamp(leftPower, -1.0f, 1.0f); rightPower = std::clamp(rightPower, -1.0f, 1.0f); - if (left_) left_->setPower(leftPower, ownerLeft_); - if (right_) right_->setPower(rightPower, ownerRight_); + if (left_) left_->setPower(leftPower); + if (right_) right_->setPower(rightPower); } void stop(){ - if (left_) left_->setPower(0.0f, ownerLeft_); - if (right_) right_->setPower(0.0f, ownerRight_); + if (left_) left_->setPower(0.0f); + if (right_) right_->setPower(0.0f); } private: probot::motor::IMotorDriver* left_; probot::motor::IMotorDriver* right_; - void* ownerLeft_; - void* ownerRight_; }; } diff --git a/src/probot/control/closed_loop_motor.hpp b/src/probot/control/closed_loop_motor.hpp index d5ee386..6e1b1f5 100644 --- a/src/probot/control/closed_loop_motor.hpp +++ b/src/probot/control/closed_loop_motor.hpp @@ -28,20 +28,16 @@ namespace probot::control { active_mode_(ControlType::kVelocity), default_slot_velocity_(0), default_slot_position_(1), - owner_token_(this), - external_owner_(nullptr), inverted_(false) { for (int i=0;i<4;i++){ slot_cfg_[i] = {0.0f, 0.0f, 0.0f, 0.0f, -1.0f, 1.0f}; } - if (driver_) driver_->claim(owner_token_); } ~ClosedLoopMotor(){ if (driver_) { - driver_->setPower(0.0f, owner_token_); - driver_->release(owner_token_); + driver_->setPower(0.0f); } } @@ -131,29 +127,14 @@ namespace probot::control { bool setPowerDirect(float power){ if (!driver_) return false; - if (external_owner_) return false; // Respect external ownership - return driver_->setPower(power, owner_token_); + return driver_->setPower(power); } - // IMotor interface (external ownership control). External owner must claim/release. - bool claim(void* owner) override { - if (external_owner_ && external_owner_ != owner) return false; + bool setPower(float power) override { if (!driver_) return false; - external_owner_ = owner; - return true; - } - void release(void* owner) override { - if (!driver_ || external_owner_ != owner) return; - driver_->setPower(0.0f, owner_token_); - external_owner_ = nullptr; - } - bool setPower(float power, void* owner) override { - if (!driver_ || external_owner_ != owner) return false; float p = inverted_ ? -power : power; - return driver_->setPower(p, owner_token_); + return driver_->setPower(p); } - bool isClaimed() const override { return external_owner_ != nullptr; } - void* currentOwner() const override { return external_owner_; } void setInverted(bool inverted) override { inverted_ = inverted; @@ -165,7 +146,7 @@ namespace probot::control { if (!encoder_ || !pid_ || !driver_) return; if (timeout_ms_ > 0 && (now_ms - last_ref_ms_.load()) > timeout_ms_){ - driver_->setPower(0.0f, owner_token_); + driver_->setPower(0.0f); last_output_ = 0.0f; return; } @@ -174,7 +155,7 @@ namespace probot::control { float target_val = target_value_.load(); float output = inverted_ ? -target_val : target_val; ref_value_.store(target_val); - driver_->setPower(output, owner_token_); + driver_->setPower(output); last_measurement_ = target_val; last_output_ = output; return; @@ -223,7 +204,7 @@ namespace probot::control { float cmd = pid_out + ff; cmd = std::clamp(cmd, slot_cfg_[slot].out_min, slot_cfg_[slot].out_max); - driver_->setPower(cmd, owner_token_); + driver_->setPower(cmd); last_measurement_ = meas; last_output_ = cmd; @@ -383,8 +364,6 @@ namespace probot::control { ControlType profile_mode_ = ControlType::kPercent; std::unique_ptr motion_profile_; - void* owner_token_; - void* external_owner_; bool inverted_; float last_measurement_ = 0.0f; float last_output_ = 0.0f; diff --git a/src/probot/control/closed_loop_motor_group.hpp b/src/probot/control/closed_loop_motor_group.hpp index 1a2894c..344a013 100644 --- a/src/probot/control/closed_loop_motor_group.hpp +++ b/src/probot/control/closed_loop_motor_group.hpp @@ -6,7 +6,7 @@ namespace probot::control { class ClosedLoopMotorGroup : public IMotorController { public: ClosedLoopMotorGroup(IMotorController* a, IMotorController* b) - : a_(a), b_(b), owner_(nullptr), inverted_(false) {} + : a_(a), b_(b), inverted_(false) {} // Group control API void setSetpoint(float value, ControlType mode, int slot = -1) override { @@ -62,29 +62,12 @@ namespace probot::control { } // IMotor for raw power when needed - bool claim(void* owner) override { - if (owner_ && owner_ != owner) return false; - if (!a_ || !b_) return false; - if (!a_->claim(owner)) return false; - if (!b_->claim(owner)) { a_->release(owner); return false; } - owner_ = owner; - return true; - } - void release(void* owner) override { - if (owner_ != owner) return; - if (b_) b_->release(owner); - if (a_) a_->release(owner); - owner_ = nullptr; - } - bool setPower(float power, void* owner) override { - if (owner_ != owner) return false; + bool setPower(float power) override { float p = inverted_ ? -power : power; - bool ok1 = a_ ? a_->setPower(p, owner) : false; - bool ok2 = b_ ? b_->setPower(p, owner) : false; + bool ok1 = a_ ? a_->setPower(p) : false; + bool ok2 = b_ ? b_->setPower(p) : false; return ok1 && ok2; } - bool isClaimed() const override { return owner_ != nullptr; } - void* currentOwner() const override { return owner_; } void setInverted(bool inverted) override { inverted_ = inverted; @@ -96,7 +79,6 @@ namespace probot::control { private: IMotorController* a_; IMotorController* b_; - void* owner_; bool inverted_; }; } // namespace probot::control diff --git a/src/probot/devices/motors/boardoza_ba6208_driver.cpp b/src/probot/devices/motors/boardoza_ba6208_driver.cpp index 383d786..84ab72b 100644 --- a/src/probot/devices/motors/boardoza_ba6208_driver.cpp +++ b/src/probot/devices/motors/boardoza_ba6208_driver.cpp @@ -50,20 +50,7 @@ void BoardozaBA6208Driver::setBrakeMode(bool enabled){ applyStop(); } -bool BoardozaBA6208Driver::claim(void* owner){ - if (owner_ && owner_ != owner) return false; - owner_ = owner; - return true; -} - -void BoardozaBA6208Driver::release(void* owner){ - if (owner_ != owner) return; - owner_ = nullptr; - applyStop(); -} - -bool BoardozaBA6208Driver::setPower(float power, void* owner){ - if (owner_ && owner_ != owner) return false; +bool BoardozaBA6208Driver::setPower(float power){ ensureInitialized(); if (!initialized_) return false; diff --git a/src/probot/devices/motors/boardoza_ba6208_driver.hpp b/src/probot/devices/motors/boardoza_ba6208_driver.hpp index bcb4d76..230c9c4 100644 --- a/src/probot/devices/motors/boardoza_ba6208_driver.hpp +++ b/src/probot/devices/motors/boardoza_ba6208_driver.hpp @@ -18,11 +18,7 @@ class BoardozaBA6208Driver : public IMotorDriver { bool brakeMode() const { return brake_mode_; } // IMotorDriver overrides - bool claim(void* owner) override; - void release(void* owner) override; - bool setPower(float power, void* owner) override; - bool isClaimed() const override { return owner_ != nullptr; } - void* currentOwner() const override { return owner_; } + bool setPower(float power) override; void setInverted(bool inverted) override { inverted_ = inverted; } bool getInverted() const override { return inverted_; } @@ -39,7 +35,6 @@ class BoardozaBA6208Driver : public IMotorDriver { uint32_t pwm_frequency_; uint8_t pwm_resolution_; - void* owner_ = nullptr; bool inverted_ = false; bool initialized_ = false; bool brake_mode_ = true; diff --git a/src/probot/devices/motors/boardoza_vnh_motor_driver.cpp b/src/probot/devices/motors/boardoza_vnh_motor_driver.cpp index dbdb041..67d33c7 100644 --- a/src/probot/devices/motors/boardoza_vnh_motor_driver.cpp +++ b/src/probot/devices/motors/boardoza_vnh_motor_driver.cpp @@ -85,21 +85,7 @@ void BoardozaVNHMotorDriver::setBrakeStrength(float dutyFraction){ } } -bool BoardozaVNHMotorDriver::claim(void* owner){ - if (owner_ && owner_ != owner) return false; - owner_ = owner; - return true; -} - -void BoardozaVNHMotorDriver::release(void* owner){ - if (owner_ != owner) return; - owner_ = nullptr; - applyStop(); -} - -bool BoardozaVNHMotorDriver::setPower(float power, void* owner){ - if (owner_ && owner_ != owner) return false; - +bool BoardozaVNHMotorDriver::setPower(float power){ ensureInitialized(); if (!initialized_) return false; diff --git a/src/probot/devices/motors/boardoza_vnh_motor_driver.hpp b/src/probot/devices/motors/boardoza_vnh_motor_driver.hpp index e5efb48..8d3d995 100644 --- a/src/probot/devices/motors/boardoza_vnh_motor_driver.hpp +++ b/src/probot/devices/motors/boardoza_vnh_motor_driver.hpp @@ -20,11 +20,7 @@ class BoardozaVNHMotorDriver : public IMotorDriver { float brakeStrength() const { return brake_strength_; } // IMotorDriver - bool claim(void* owner) override; - void release(void* owner) override; - bool setPower(float power, void* owner) override; - bool isClaimed() const override { return owner_ != nullptr; } - void* currentOwner() const override { return owner_; } + bool setPower(float power) override; void setInverted(bool inverted) override { inverted_ = inverted; } bool getInverted() const override { return inverted_; } @@ -40,7 +36,6 @@ class BoardozaVNHMotorDriver : public IMotorDriver { int pwm_pin_; int ena_pin_; int enb_pin_; - void* owner_ = nullptr; bool inverted_ = false; bool initialized_ = false; bool brake_mode_ = true; diff --git a/src/probot/devices/motors/imotor_driver.hpp b/src/probot/devices/motors/imotor_driver.hpp index 887529e..4e54e30 100644 --- a/src/probot/devices/motors/imotor_driver.hpp +++ b/src/probot/devices/motors/imotor_driver.hpp @@ -1,13 +1,8 @@ #pragma once -#include namespace probot::motor { struct IMotorDriver { - virtual bool claim(void* owner) = 0; // exclusive write claim - virtual void release(void* owner) = 0; // release claim if owner matches - virtual bool setPower(float power, void* owner) = 0; // -1.0..1.0 normalized output - virtual bool isClaimed() const = 0; - virtual void* currentOwner() const = 0; + virtual bool setPower(float power) = 0; // -1.0..1.0 normalized output // Direction inversion: if inverted, drivers should negate applied power internally virtual void setInverted(bool inverted) = 0; @@ -15,4 +10,4 @@ namespace probot::motor { virtual ~IMotorDriver() {} }; -} // namespace probot::motor +} // namespace probot::motor diff --git a/src/probot/devices/motors/motor_group.hpp b/src/probot/devices/motors/motor_group.hpp index 3e2ef73..b745bb2 100644 --- a/src/probot/devices/motors/motor_group.hpp +++ b/src/probot/devices/motors/motor_group.hpp @@ -5,37 +5,16 @@ namespace probot::motor { class MotorGroup : public IMotorDriver { public: MotorGroup(IMotorDriver* a, IMotorDriver* b) - : a_(a), b_(b), owner_(nullptr), inverted_(false) {} + : a_(a), b_(b), inverted_(false) {} - bool claim(void* owner) override { + bool setPower(float power) override { if (!a_ || !b_) return false; - if (owner_) return owner_ == owner; - if (!a_->claim(owner)) return false; - if (!b_->claim(owner)) { a_->release(owner); return false; } - owner_ = owner; - return true; - } - - void release(void* owner) override { - if (!a_ || !b_) return; - if (owner_ != owner) return; - b_->release(owner); - a_->release(owner); - owner_ = nullptr; - } - - bool setPower(float power, void* owner) override { - if (!a_ || !b_) return false; - if (owner_ != owner) return false; float p = inverted_ ? -power : power; - bool ok1 = a_->setPower(p, owner); - bool ok2 = b_->setPower(p, owner); + bool ok1 = a_->setPower(p); + bool ok2 = b_->setPower(p); return ok1 && ok2; } - bool isClaimed() const override { return owner_ != nullptr; } - void* currentOwner() const override { return owner_; } - void setInverted(bool inverted) override { inverted_ = inverted; if (a_) a_->setInverted(inverted); @@ -46,7 +25,6 @@ namespace probot::motor { private: IMotorDriver* a_; IMotorDriver* b_; - void* owner_; bool inverted_; }; } // namespace probot::motor diff --git a/src/probot/devices/motors/motor_handle.hpp b/src/probot/devices/motors/motor_handle.hpp index 1443462..cbc9fa5 100644 --- a/src/probot/devices/motors/motor_handle.hpp +++ b/src/probot/devices/motors/motor_handle.hpp @@ -8,23 +8,17 @@ namespace probot::motor { class MotorHandle { public: explicit MotorHandle(IMotorDriver& motor) - : _motor(&motor), _owner(this) - { - _motor->claim(_owner); - } + : _motor(&motor) {} - void setPower(float value){ _motor->setPower(value, _owner); } + void setPower(float value){ _motor->setPower(value); } void setInverted(bool inv){ _motor->setInverted(inv); } bool getInverted() const { return _motor->getInverted(); } - void release(){ _motor->release(_owner); } - IMotorDriver& underlying() { return *_motor; } const IMotorDriver& underlying() const { return *_motor; } private: IMotorDriver* _motor; - void* _owner; // unique owner token }; } // namespace probot::motor diff --git a/src/probot/test/test_motor.hpp b/src/probot/test/test_motor.hpp index 9af3828..7d06ad7 100644 --- a/src/probot/test/test_motor.hpp +++ b/src/probot/test/test_motor.hpp @@ -4,29 +4,23 @@ namespace probot::test { class TestMotor : public probot::motor::IMotorDriver { public: - bool claim(void* owner) override { - if (owner_ == nullptr || owner_ == owner){ owner_ = owner; return true; } - return false; - } - void release(void* owner) override { if (owner_ == owner) owner_ = nullptr; } - bool setPower(float power, void* owner) override { - if (owner_ != owner) return false; + bool setPower(float power) override { if (power < -1.0f) power = -1.0f; else if (power > 1.0f) power = 1.0f; - last_cmd_ = power; + commanded_ = power; + last_cmd_ = inverted_ ? -power : power; return true; } - bool isClaimed() const override { return owner_ != nullptr; } - void* currentOwner() const override { return owner_; } void setInverted(bool inverted) override { inverted_ = inverted; } bool getInverted() const override { return inverted_; } - float appliedPower() const { return inverted_ ? -last_cmd_ : last_cmd_; } + float appliedPower() const { return last_cmd_; } + float commandedPower() const { return commanded_; } private: - void* owner_ = nullptr; bool inverted_= false; float last_cmd_= 0.0f; + float commanded_= 0.0f; }; } // namespace probot::test diff --git a/tests/test_chassis.cpp b/tests/test_chassis.cpp index fa8c02d..d85e6a2 100644 --- a/tests/test_chassis.cpp +++ b/tests/test_chassis.cpp @@ -13,14 +13,9 @@ namespace { struct DummyMotor : probot::motor::IMotorDriver { - void* owner = nullptr; float lastPower = 0.0f; bool inverted = false; - bool claim(void* o) override { if (owner && owner != o) return false; owner = o; return true; } - void release(void* o) override { if (owner == o){ owner = nullptr; lastPower = 0.0f; } } - bool setPower(float power, void* o) override { if (owner != o) return false; lastPower = inverted ? -power : power; return true; } - bool isClaimed() const override { return owner != nullptr; } - void* currentOwner() const override { return owner; } + bool setPower(float power) override { lastPower = inverted ? -power : power; return true; } void setInverted(bool inv) override { inverted = inv; } bool getInverted() const override { return inverted; } }; @@ -33,7 +28,6 @@ namespace { }; struct MockMotorController : probot::control::IMotorController { - void* owner = nullptr; float lastSetpointValue = 0.0f; probot::control::ControlType lastMode = probot::control::ControlType::kPercent; int lastSlot = -1; @@ -43,20 +37,11 @@ namespace { bool setPowerCalled = false; float lastPower = 0.0f; - bool claim(void* o) override { - if (owner && owner != o) return false; - owner = o; - return true; - } - void release(void* o) override { if (owner == o) owner = nullptr; } - bool setPower(float power, void* o) override { - if (owner != o) return false; + bool setPower(float power) override { setPowerCalled = true; lastPower = inverted ? -power : power; return true; } - bool isClaimed() const override { return owner != nullptr; } - void* currentOwner() const override { return owner; } void setInverted(bool inv) override { inverted = inv; } bool getInverted() const override { return inverted; } @@ -150,8 +135,6 @@ TEST_CASE(nfr_tank_drive_closed_loop_should_command_power){ probot::control::ClosedLoopMotor clR(&encR, &pidR, &motorR, 1.0f, 1.0f); clL.setTimeoutMs(0); clR.setTimeoutMs(0); - EXPECT_TRUE(motorL.isClaimed()); - EXPECT_TRUE(motorR.isClaimed()); probot::chassis::NfrAdvancedTankDrive chassis(&clL, &clR); chassis.resetPose(probot::control::Pose2d(), 0.0f, 0.0f); @@ -177,10 +160,6 @@ TEST_CASE(nfr_mecanum_drive_closed_loop_should_command_power){ clFR.setTimeoutMs(0); clRL.setTimeoutMs(0); clRR.setTimeoutMs(0); - EXPECT_TRUE(motorFL.isClaimed()); - EXPECT_TRUE(motorFR.isClaimed()); - EXPECT_TRUE(motorRL.isClaimed()); - EXPECT_TRUE(motorRR.isClaimed()); probot::chassis::NfrAdvancedMecanumDrive chassis(&clFL, &clFR, &clRL, &clRR); probot::control::kinematics::WheelPositions4 wheels{0.0f, 0.0f, 0.0f, 0.0f}; diff --git a/tests/test_closed_loop.cpp b/tests/test_closed_loop.cpp index ffa8db6..0ac7da0 100644 --- a/tests/test_closed_loop.cpp +++ b/tests/test_closed_loop.cpp @@ -19,25 +19,13 @@ namespace { }; struct MotorStub : probot::motor::IMotorDriver { - void* owner = nullptr; float lastPower = 0.0f; bool inverted = false; - bool claim(void* o) override { - if (owner && owner != o) return false; - owner = o; - return true; - } - void release(void* o) override { - if (owner == o){ owner = nullptr; lastPower = 0.0f; } - } - bool setPower(float power, void* o) override { - if (owner != o) return false; + bool setPower(float power) override { lastPower = inverted ? -power : power; return true; } - bool isClaimed() const override { return owner != nullptr; } - void* currentOwner() const override { return owner; } void setInverted(bool inv) override { inverted = inv; } bool getInverted() const override { return inverted; } }; @@ -50,24 +38,14 @@ namespace { float output = 0.0f; float lastCommand = 0.0f; bool inverted = false; - void* owner = nullptr; probot::control::MotionProfileType profileType = probot::control::MotionProfileType::kNone; probot::control::MotionProfileConfig profileCfg{}; - bool claim(void* o) override { - if (owner && owner != o) return false; - owner = o; - return true; - } - void release(void* o) override { if (owner == o) owner = nullptr; } - bool setPower(float power, void* o) override { - if (owner != o) return false; + bool setPower(float power) override { lastCommand = power; output = inverted ? -power : power; return true; } - bool isClaimed() const override { return owner != nullptr; } - void* currentOwner() const override { return owner; } void setInverted(bool inv) override { inverted = inv; } bool getInverted() const override { return inverted; } @@ -135,19 +113,14 @@ TEST_CASE(closed_loop_motor_group_broadcast){ EXPECT_TRUE(a.mode == probot::control::ControlType::kPosition); EXPECT_TRUE(b.mode == probot::control::ControlType::kPosition); - float token = 0.0f; - EXPECT_TRUE(group.claim(&token)); - EXPECT_TRUE(group.setPower(0.5f, &token)); + EXPECT_TRUE(group.setPower(0.5f)); EXPECT_NEAR(a.output, 0.5f, 1e-5f); EXPECT_NEAR(b.output, 0.5f, 1e-5f); group.setInverted(true); EXPECT_TRUE(group.getInverted()); - EXPECT_TRUE(group.setPower(0.5f, &token)); + EXPECT_TRUE(group.setPower(0.5f)); EXPECT_NEAR(a.lastCommand, -0.5f, 1e-5f); - - group.release(&token); - EXPECT_TRUE(!a.isClaimed()); } TEST_CASE(closed_loop_motor_percent_and_timeout){ @@ -174,24 +147,6 @@ TEST_CASE(closed_loop_motor_percent_and_timeout){ EXPECT_NEAR(driver.lastPower, 0.0f, 1e-5f); } -TEST_CASE(closed_loop_motor_external_claim_should_allow_control){ - EncoderStub encoder; - MotorStub driver; - auto cfg = makePid(0.2f); - probot::control::PID pid(cfg); - probot::control::ClosedLoopMotor controller(&encoder, &pid, &driver, 1.0f, 0.001f); - controller.setTimeoutMs(0); - controller.setPidSlotConfig(0, cfg); - EXPECT_TRUE(driver.owner != nullptr); - - float externalToken = 1.0f; - EXPECT_TRUE(controller.claim(&externalToken)); - EXPECT_TRUE(controller.setPower(0.3f, &externalToken)); - EXPECT_NEAR(driver.lastPower, 0.3f, 1e-5f); - controller.release(&externalToken); - EXPECT_TRUE(!controller.isClaimed()); -} - TEST_CASE(closed_loop_motor_trapezoid_profile_ramps){ EncoderStub encoder; MotorStub driver; diff --git a/tests/test_devices.cpp b/tests/test_devices.cpp index 4df611e..91df47e 100644 --- a/tests/test_devices.cpp +++ b/tests/test_devices.cpp @@ -9,47 +9,36 @@ namespace { struct MotorStub : probot::motor::IMotorDriver { - void* owner = nullptr; float lastPower = 0.0f; float lastCommand = 0.0f; bool inverted = false; - bool claim(void* o) override { if (owner && owner != o) return false; owner = o; return true; } - void release(void* o) override { if (owner == o){ owner = nullptr; lastPower = 0.0f; } } - bool setPower(float power, void* o) override { if (owner != o) return false; lastCommand = power; lastPower = inverted ? -power : power; return true; } - bool isClaimed() const override { return owner != nullptr; } - void* currentOwner() const override { return owner; } + bool setPower(float power) override { lastCommand = power; lastPower = inverted ? -power : power; return true; } void setInverted(bool inv) override { inverted = inv; } bool getInverted() const override { return inverted; } }; } -TEST_CASE(motor_group_claim_and_invert){ +TEST_CASE(motor_group_power_and_invert){ MotorStub a, b; probot::motor::MotorGroup group(&a, &b); - int token = 42; - EXPECT_TRUE(group.claim(&token)); - EXPECT_TRUE(group.setPower(0.3f, &token)); + EXPECT_TRUE(group.setPower(0.3f)); EXPECT_NEAR(a.lastPower, 0.3f, 1e-5f); EXPECT_NEAR(b.lastPower, 0.3f, 1e-5f); group.setInverted(true); - EXPECT_TRUE(group.setPower(0.4f, &token)); + EXPECT_TRUE(group.setPower(0.4f)); EXPECT_NEAR(a.lastCommand, -0.4f, 1e-5f); - group.release(&token); - EXPECT_TRUE(!a.isClaimed()); } -TEST_CASE(motor_handle_claims_motor){ +TEST_CASE(motor_handle_controls_motor){ probot::motor::NullMotor motor; - { - probot::motor::MotorHandle handle(motor); - handle.setPower(0.5f); - EXPECT_TRUE(motor.isClaimed()); - handle.setInverted(true); - EXPECT_TRUE(handle.getInverted()); - handle.release(); - } - EXPECT_TRUE(!motor.isClaimed()); + probot::motor::MotorHandle handle(motor); + handle.setPower(0.5f); + EXPECT_NEAR(motor.appliedPower(), 0.5f, 1e-5f); + handle.setInverted(true); + EXPECT_TRUE(handle.getInverted()); + handle.setPower(0.2f); + EXPECT_NEAR(motor.appliedPower(), -0.2f, 1e-5f); } static_assert(std::is_base_of::value, diff --git a/tests/test_mechanisms.cpp b/tests/test_mechanisms.cpp index 0c0e3aa..bab65a9 100644 --- a/tests/test_mechanisms.cpp +++ b/tests/test_mechanisms.cpp @@ -22,11 +22,7 @@ namespace { probot::control::MotionProfileType profileType = probot::control::MotionProfileType::kNone; probot::control::MotionProfileConfig profileCfg{}; - bool claim(void*) override { return true; } - void release(void*) override {} - bool setPower(float, void*) override { return true; } - bool isClaimed() const override { return false; } - void* currentOwner() const override { return nullptr; } + bool setPower(float) override { return true; } void setInverted(bool) override {} bool getInverted() const override { return false; } From 626f200a2708eee5ceadacb60c9a2671e1300fad Mon Sep 17 00:00:00 2001 From: tunapro Date: Thu, 16 Oct 2025 13:55:17 +0300 Subject: [PATCH 02/26] fix(motor): correct inversion handling --- src/probot/control/closed_loop_motor.hpp | 21 ++++++++++++------- .../control/closed_loop_motor_group.hpp | 5 ++--- src/probot/devices/motors/motor_group.hpp | 5 ++--- tests/test_closed_loop.cpp | 4 +++- tests/test_devices.cpp | 3 ++- 5 files changed, 23 insertions(+), 15 deletions(-) diff --git a/src/probot/control/closed_loop_motor.hpp b/src/probot/control/closed_loop_motor.hpp index 6e1b1f5..5f408bb 100644 --- a/src/probot/control/closed_loop_motor.hpp +++ b/src/probot/control/closed_loop_motor.hpp @@ -127,13 +127,20 @@ namespace probot::control { bool setPowerDirect(float power){ if (!driver_) return false; - return driver_->setPower(power); + bool ok = driver_->setPower(power); + if (ok){ + last_output_ = inverted_ ? -power : power; + } + return ok; } bool setPower(float power) override { if (!driver_) return false; - float p = inverted_ ? -power : power; - return driver_->setPower(p); + bool ok = driver_->setPower(power); + if (ok){ + last_output_ = inverted_ ? -power : power; + } + return ok; } void setInverted(bool inverted) override { @@ -153,11 +160,11 @@ namespace probot::control { if (active_mode_ == ControlType::kPercent){ float target_val = target_value_.load(); - float output = inverted_ ? -target_val : target_val; + float applied = inverted_ ? -target_val : target_val; ref_value_.store(target_val); - driver_->setPower(output); + driver_->setPower(target_val); last_measurement_ = target_val; - last_output_ = output; + last_output_ = applied; return; } @@ -206,7 +213,7 @@ namespace probot::control { driver_->setPower(cmd); last_measurement_ = meas; - last_output_ = cmd; + last_output_ = inverted_ ? -cmd : cmd; #ifndef PROBOT_CLM_NOLOG Serial.printf("[CLM ] mode=%s ref=%.3f meas=%.3f err=%.3f out=%.3f slot=%d\n", diff --git a/src/probot/control/closed_loop_motor_group.hpp b/src/probot/control/closed_loop_motor_group.hpp index 344a013..af4c015 100644 --- a/src/probot/control/closed_loop_motor_group.hpp +++ b/src/probot/control/closed_loop_motor_group.hpp @@ -63,9 +63,8 @@ namespace probot::control { // IMotor for raw power when needed bool setPower(float power) override { - float p = inverted_ ? -power : power; - bool ok1 = a_ ? a_->setPower(p) : false; - bool ok2 = b_ ? b_->setPower(p) : false; + bool ok1 = a_ ? a_->setPower(power) : false; + bool ok2 = b_ ? b_->setPower(power) : false; return ok1 && ok2; } diff --git a/src/probot/devices/motors/motor_group.hpp b/src/probot/devices/motors/motor_group.hpp index b745bb2..7e4cc3e 100644 --- a/src/probot/devices/motors/motor_group.hpp +++ b/src/probot/devices/motors/motor_group.hpp @@ -9,9 +9,8 @@ namespace probot::motor { bool setPower(float power) override { if (!a_ || !b_) return false; - float p = inverted_ ? -power : power; - bool ok1 = a_->setPower(p); - bool ok2 = b_->setPower(p); + bool ok1 = a_->setPower(power); + bool ok2 = b_->setPower(power); return ok1 && ok2; } diff --git a/tests/test_closed_loop.cpp b/tests/test_closed_loop.cpp index 0ac7da0..96cb36a 100644 --- a/tests/test_closed_loop.cpp +++ b/tests/test_closed_loop.cpp @@ -116,11 +116,13 @@ TEST_CASE(closed_loop_motor_group_broadcast){ EXPECT_TRUE(group.setPower(0.5f)); EXPECT_NEAR(a.output, 0.5f, 1e-5f); EXPECT_NEAR(b.output, 0.5f, 1e-5f); + EXPECT_NEAR(a.lastCommand, 0.5f, 1e-5f); group.setInverted(true); EXPECT_TRUE(group.getInverted()); EXPECT_TRUE(group.setPower(0.5f)); - EXPECT_NEAR(a.lastCommand, -0.5f, 1e-5f); + EXPECT_NEAR(a.output, -0.5f, 1e-5f); + EXPECT_NEAR(a.lastCommand, 0.5f, 1e-5f); } TEST_CASE(closed_loop_motor_percent_and_timeout){ diff --git a/tests/test_devices.cpp b/tests/test_devices.cpp index 91df47e..f8c9728 100644 --- a/tests/test_devices.cpp +++ b/tests/test_devices.cpp @@ -27,7 +27,8 @@ TEST_CASE(motor_group_power_and_invert){ group.setInverted(true); EXPECT_TRUE(group.setPower(0.4f)); - EXPECT_NEAR(a.lastCommand, -0.4f, 1e-5f); + EXPECT_NEAR(a.lastPower, -0.4f, 1e-5f); + EXPECT_NEAR(a.lastCommand, 0.4f, 1e-5f); } TEST_CASE(motor_handle_controls_motor){ From 1b552c3d899fec5eb08cb71d2177ae960f37d46b Mon Sep 17 00:00:00 2001 From: tunapro Date: Thu, 16 Oct 2025 15:20:02 +0300 Subject: [PATCH 03/26] feat: add ui simulator variants --- ui-testing/README.md | 76 ++++ ui-testing/server.py | 468 ++++++++++++++++++++++++ ui-testing/variants/aero_hud.html | 398 ++++++++++++++++++++ ui-testing/variants/base.html | 67 ++++ ui-testing/variants/circuit_glow.html | 365 ++++++++++++++++++ ui-testing/variants/command_deck.html | 430 ++++++++++++++++++++++ ui-testing/variants/control_tower.html | 352 ++++++++++++++++++ ui-testing/variants/minimal_stack.html | 367 +++++++++++++++++++ ui-testing/variants/neon_grid.html | 356 ++++++++++++++++++ ui-testing/variants/pit_wall.html | 412 +++++++++++++++++++++ ui-testing/variants/retro_terminal.html | 287 +++++++++++++++ ui-testing/variants/zen_flow.html | 359 ++++++++++++++++++ 12 files changed, 3937 insertions(+) create mode 100644 ui-testing/README.md create mode 100644 ui-testing/server.py create mode 100644 ui-testing/variants/aero_hud.html create mode 100644 ui-testing/variants/base.html create mode 100644 ui-testing/variants/circuit_glow.html create mode 100644 ui-testing/variants/command_deck.html create mode 100644 ui-testing/variants/control_tower.html create mode 100644 ui-testing/variants/minimal_stack.html create mode 100644 ui-testing/variants/neon_grid.html create mode 100644 ui-testing/variants/pit_wall.html create mode 100644 ui-testing/variants/retro_terminal.html create mode 100644 ui-testing/variants/zen_flow.html diff --git a/ui-testing/README.md b/ui-testing/README.md new file mode 100644 index 0000000..8b48778 --- /dev/null +++ b/ui-testing/README.md @@ -0,0 +1,76 @@ +# UI Testing Helpers + +Bu klasör, ESP32'ye ihtiyaç duymadan driver station arayüzünü çalıştırmak için +kullanabileceğimiz küçük bir Python sunucusu içerir. Sunucu, +`src/platform/esp32s3/web/index_html.h` dosyasındaki HTML verisini doğrudan +okur, böylece ESP'ye flash edeceğimiz içerikle birebir aynı çıktıyı görürüz. + +## Başlangıç + +```bash +python3 ui-testing/server.py +# veya belirli bir port için: +python3 ui-testing/server.py --port 9000 --open-browser +``` + +- Sunucu açıldığında `http://localhost:/` adresinden UI'ı görüntüleyebilirsiniz. +- Frontend'in kullandığı `/robotControl`, `/updateController` ve `/getBattery` + uç noktaları temel stub cevapları döndürür; bu sayede UI hata vermeden çalışır. +- Konsolda yapılan isteklere dair loglar görünür, böylece gamepad POST'ları veya + robot komutlarını takip edebilirsiniz. + +## Boyut Raporu + +Arayüzün ne kadar flash alanı kapladığını ve örnek bir derlemede toplam +kullanımı görmek için: + +```bash +# Sadece HTML boyutunu ölç +python3 ui-testing/server.py --report-only + +# HTML + DriverStationDemo derlemesiyle toplam kullanım raporu +python3 ui-testing/server.py --report-only --build-report +``` + +- HTML boyutu 6584 byte civarındadır ve 4 MiB flash'ın yaklaşık %0.16'sını kaplar. +- `--build-report` seçeneği `arduino-cli` ile + `examples/__library_impl/DriverStationDemo/DriverStationDemo.ino` dosyasını + derler ve hem flash hem de RAM kullanımını raporlar. + Gerekirse `--example`, `--fqbn` veya `--build-dir` argümanlarıyla özelleştirebilirsiniz. +- Sadece rapor alıp çıkmak için `--report-only` yeterlidir; sunucu başlatılmaz. + +## Varyasyonlarla Çalışma + +- `ui-testing/variants/` klasöründe mevcut arayüzün birebir kopyası (`base.html`) + ve dokuz farklı konsept örneği bulunuyor: + `command_deck.html`, `aero_hud.html`, `pit_wall.html`, `minimal_stack.html`, + `retro_terminal.html`, `neon_grid.html`, `control_tower.html`, + `zen_flow.html`, `circuit_glow.html`. Yeni tasarımlar için bu dosyaları + başlangıç noktası olarak kopyalayıp düzenleyebilirsiniz. +- Seçili bir varyasyonu denemek için: + +```bash +python3 ui-testing/server.py --html ui-testing/variants/base.html +``` + +- `--html` parametresi verildiğinde hem sunucu hem de boyut raporu bu dosyayı + kullanır. Parametreyi boş bırakırsanız kütüphanedeki gömülü `index_html.h` + okunmaya devam eder (donanım gerçekliğini test etmek için yararlı). + +## Tüm Varyantları Aynı Anda Görmek + +- 10 örnek tasarımı (port 9030–9039) aynı anda açmak için: + + ```bash + python3 ui-testing/server.py --suite + ``` + +- Varsayılan port aralığı 9030'dan başlar. Gerekirse `--suite-base-port` veya + `--suite-limit` ile özelleştirebilirsiniz. Sadece rapor almak isterseniz + `--report-only --suite` komutu yeterlidir; sunucular başlatılmaz. + +## Notlar + +- Sunucu HTML içeriğini her istekte yeniden okuduğu için `index_html.h` + üzerinde yaptığınız değişiklikleri görmek için sunucuyu yeniden başlatmanıza gerek yoktur. +- Python standart kütüphanesinden başka bir bağımlılık gerektirmez. diff --git a/ui-testing/server.py b/ui-testing/server.py new file mode 100644 index 0000000..f08f9be --- /dev/null +++ b/ui-testing/server.py @@ -0,0 +1,468 @@ +#!/usr/bin/env python3 +""" +Lightweight local simulator for the Probot driver station web UI. + +It serves the HTML bundle embedded in `src/platform/esp32s3/web/index_html.h` +and provides stub endpoints so the frontend behaves as if it were talking to +the ESP32 firmware. This lets us iterate on the UI without flashing hardware. +""" +from __future__ import annotations + +import argparse +import http.server +import json +import logging +import re +import shutil +import socketserver +import subprocess +import sys +import threading +import time +import urllib.parse +from pathlib import Path +from typing import Dict, List, Optional, Tuple + +REPO_ROOT = Path(__file__).resolve().parents[1] +INDEX_HEADER = REPO_ROOT / "src/platform/esp32s3/web/index_html.h" +START_TOKEN = 'R"=====(' +END_TOKEN = ')=====";' +ESP32S3_FLASH_BYTES = 4 * 1024 * 1024 # 4 MiB default flash size +VARIANTS_DIR = Path(__file__).resolve().parent / "variants" +def load_embedded_html() -> str: + """Extract the HTML payload from the C++ header without modifying the source.""" + try: + text = INDEX_HEADER.read_text(encoding="utf-8") + except FileNotFoundError as exc: # pragma: no cover - guard rail + raise SystemExit( + f"Could not find driver station header at {INDEX_HEADER}. " + "Run from inside the repository root." + ) from exc + + try: + start = text.index(START_TOKEN) + len(START_TOKEN) + end = text.index(END_TOKEN, start) + except ValueError as exc: # pragma: no cover - guard rail + raise SystemExit( + "Unable to locate embedded HTML block. " + "Expected tokens were missing in index_html.h." + ) from exc + + # Preserve exact formatting so we are looking at the same bytes flashed to the ESP. + return text[start:end] + + +def load_html(html_override: Optional[Path]) -> str: + if html_override: + return html_override.read_text(encoding="utf-8") + return load_embedded_html() + + +def compute_html_stats(html: str) -> Tuple[int, float]: + """Return payload size (including terminator) and flash percentage.""" + byte_count = len(html.encode("utf-8")) + 1 # include null terminator stored in PROGMEM + percent = (byte_count / ESP32S3_FLASH_BYTES) * 100.0 + return byte_count, percent + + +def run_build_report( + example: Path, + build_dir: Path, + arduino_cli: str, + fqbn: str, +) -> Optional[Dict[str, float]]: + """Compile the chosen example and parse flash/RAM usage.""" + if shutil.which(arduino_cli) is None: + logging.error("arduino-cli not found on PATH; skipping build report.") + return None + + if not example.exists(): + logging.error("Example sketch not found at %s", example) + return None + + build_dir.mkdir(parents=True, exist_ok=True) + + cmd = [ + arduino_cli, + "compile", + "--fqbn", + fqbn, + "--warnings", + "none", + "--library", + str(REPO_ROOT), + "--build-path", + str(build_dir), + str(example), + ] + + logging.info("Running: %s", " ".join(cmd)) + proc = subprocess.run(cmd, capture_output=True, text=True) + output = (proc.stdout or "") + (proc.stderr or "") + + if proc.returncode != 0: + logging.error("arduino-cli compile failed with exit code %s", proc.returncode) + logging.error(output.strip()) + return None + + flash_match = re.search( + r"Sketch uses (\d+) bytes \(~?([0-9.]+)%\) of program storage space\. Maximum is (\d+) bytes\.", + output, + ) + ram_match = re.search( + r"Global variables use (\d+) bytes \(~?([0-9.]+)%\) of dynamic memory, " + r"leaving (\d+) bytes for local variables\. Maximum is (\d+) bytes\.", + output, + ) + + if not flash_match: + logging.warning("Could not parse flash usage from arduino-cli output.") + logging.debug(output) + return None + + flash_used = int(flash_match.group(1)) + flash_percent = float(flash_match.group(2)) + flash_max = int(flash_match.group(3)) + + stats: Dict[str, float] = { + "flash_used": flash_used, + "flash_percent": flash_percent, + "flash_max": flash_max, + } + + if ram_match: + stats.update( + ram_used=int(ram_match.group(1)), + ram_percent=float(ram_match.group(2)), + ram_max=int(ram_match.group(4)), + ) + + stats["log"] = output.strip() + return stats + + +class DriverStationHandler(http.server.BaseHTTPRequestHandler): + """HTTP handler that mimics the ESP32 endpoints exposed by the driver station.""" + + server_version = "ProbotUISim/0.1" + + # Shared simulator state. This is intentionally minimal for now. + robot_state = { + "status": "init", # init | start | stop (matches UI expectations) + "autonomous": True, + "auto_period": 30, + "battery": 12.4, + "last_gamepad_update": 0.0, + } + state_lock = threading.Lock() + + def do_GET(self) -> None: # noqa: N802 - keep BaseHTTPRequestHandler signature + parsed = urllib.parse.urlparse(self.path) + path = parsed.path + + if path in ("/", "/index.html"): + self._serve_index() + return + + if path == "/robotControl": + self._handle_robot_control(parsed.query) + return + + if path == "/getBattery": + self._send_text("text/plain", f"{self.robot_state['battery']:.1f}") + return + + if path == "/favicon.ico": + self.send_error(404) + return + + self.send_error(404, f"Unsupported path: {path}") + + def do_POST(self) -> None: # noqa: N802 - keep BaseHTTPRequestHandler signature + parsed = urllib.parse.urlparse(self.path) + if parsed.path == "/updateController": + self._handle_update_controller() + return + + self.send_error(404, f"Unsupported path: {parsed.path}") + + # ===== Helpers ============================================================ + def _serve_index(self) -> None: + try: + html = load_html(getattr(self.server, "html_override", None)) + except OSError as exc: + logging.error("Failed to load HTML content: %s", exc) + self.send_error(500, "Unable to load UI content.") + return + payload = html.encode("utf-8") + self.send_response(200) + self.send_header("Content-Type", "text/html; charset=utf-8") + self.send_header("Content-Length", str(len(payload))) + self.end_headers() + self.wfile.write(payload) + + def _handle_robot_control(self, query: str) -> None: + params = urllib.parse.parse_qs(query) + cmd = params.get("cmd", [""])[0] + auto = params.get("auto", ["1"])[0] == "1" + auto_len = params.get("autoLen", ["30"])[0] + + with self.state_lock: + self.robot_state["autonomous"] = auto + try: + self.robot_state["auto_period"] = int(auto_len) + except ValueError: + pass + if cmd in ("init", "start", "stop"): + self.robot_state["status"] = cmd + + logging.info( + "robotControl cmd=%s auto=%s autoLen=%s", cmd, auto, auto_len + ) + + self._send_text("text/plain", "OK") + + def _handle_update_controller(self) -> None: + length_header = self.headers.get("Content-Length") + try: + length = int(length_header or "0") + except ValueError: + self.send_error(400, "Invalid Content-Length") + return + + body = self.rfile.read(length) + try: + payload = json.loads(body.decode("utf-8")) + except json.JSONDecodeError: + logging.warning("Received malformed controller payload: %r", body) + payload = {} + + with self.state_lock: + self.robot_state["last_gamepad_update"] = time.time() + + logging.debug("Controller update: %s", payload) + self._send_text("text/plain", "OK") + + def log_message(self, format: str, *args: Tuple[object, ...]) -> None: # type: ignore[override] + # Route all logs through logging module for consistency. + logging.info("%s - %s", self.address_string(), format % args) + + def _send_text(self, content_type: str, payload: str) -> None: + data = payload.encode("utf-8") + self.send_response(200) + self.send_header("Content-Type", content_type) + self.send_header("Content-Length", str(len(data))) + self.end_headers() + self.wfile.write(data) + + +def parse_args(argv: list[str]) -> argparse.Namespace: + parser = argparse.ArgumentParser( + description="Serve the Probot driver station UI locally." + ) + parser.add_argument( + "--port", "-p", type=int, default=8080, + help="Port to bind (default: 8080).", + ) + parser.add_argument( + "--open-browser", action="store_true", + help="Attempt to open the UI in the default browser after starting.", + ) + parser.add_argument( + "--log-level", default="INFO", + choices=("DEBUG", "INFO", "WARNING", "ERROR"), + help="Logging verbosity (default: INFO).", + ) + parser.add_argument( + "--build-report", action="store_true", + help="Run arduino-cli compile to capture flash/RAM usage before serving.", + ) + parser.add_argument( + "--report-only", action="store_true", + help="Emit size report (with optional build report) then exit.", + ) + parser.add_argument( + "--suite", action="store_true", + help="Serve every HTML variant on consecutive ports starting at --suite-base-port.", + ) + parser.add_argument( + "--suite-base-port", type=int, default=9030, + help="Base port for --suite mode (default: 9030).", + ) + parser.add_argument( + "--suite-limit", type=int, default=10, + help="Maximum number of variants to serve when --suite is enabled (default: 10).", + ) + parser.add_argument( + "--suite-dir", + default=str(VARIANTS_DIR), + help="Directory scanned for variant HTML files in --suite mode.", + ) + parser.add_argument( + "--example", + default=str(REPO_ROOT / "examples/__library_impl/DriverStationDemo/DriverStationDemo.ino"), + help="Sketch path to compile for build report.", + ) + parser.add_argument( + "--arduino-cli", + default="arduino-cli", + help="arduino-cli executable to use for build report.", + ) + parser.add_argument( + "--fqbn", + default="esp32:esp32:esp32s3", + help="FQBN passed to arduino-cli during build report.", + ) + parser.add_argument( + "--build-dir", + default=str(REPO_ROOT / ".build/ui-testing-report"), + help="Output directory for build artifacts when computing build report.", + ) + parser.add_argument( + "--html", + help="Path to an HTML variant to serve/measure instead of the embedded header.", + ) + return parser.parse_args(argv) + + +class ThreadedHTTPServer(socketserver.ThreadingMixIn, http.server.HTTPServer): + daemon_threads = True + allow_reuse_address = True + + def __init__(self, server_address, RequestHandlerClass, html_override=None): + self.html_override = html_override + super().__init__(server_address, RequestHandlerClass) + + +def main(argv: list[str]) -> int: + args = parse_args(argv) + logging.basicConfig( + level=getattr(logging, args.log_level), + format="[%(levelname)s] %(message)s", + ) + + if not INDEX_HEADER.exists(): + logging.error("Driver station header not found at %s", INDEX_HEADER) + return 1 + + if args.html and args.suite: + logging.error("--html and --suite cannot be used together.") + return 1 + + html_variants: List[Optional[Path]] = [] + if args.suite: + suite_dir = Path(args.suite_dir).resolve() + if not suite_dir.exists(): + logging.error("Variant directory not found: %s", suite_dir) + return 1 + html_variants = sorted(suite_dir.glob("*.html"))[: max(args.suite_limit, 0)] + if not html_variants: + logging.error("No HTML variants found in %s", suite_dir) + return 1 + else: + override = None + if args.html: + override = Path(args.html) + if not override.is_absolute(): + override = (REPO_ROOT / args.html).resolve() + if not override.exists(): + logging.error("HTML override file not found at %s", override) + return 1 + html_variants.append(override) + + build_stats = None + if args.build_report: + build_stats = run_build_report( + example=Path(args.example), + build_dir=Path(args.build_dir), + arduino_cli=args.arduino_cli, + fqbn=args.fqbn, + ) + + flash_mib = ESP32S3_FLASH_BYTES / (1024 * 1024) + for html_path in html_variants: + payload = load_html(html_path) + bytes_used, pct = compute_html_stats(payload) + name = html_path.name if html_path else "embedded" + logging.info( + "Embedded UI payload (%s): %d bytes (%.4f%% of %.2f MiB flash)", + name, + bytes_used, + pct, + flash_mib, + ) + if build_stats: + logging.info( + "Sketch flash usage: %d bytes (%.2f%% of %d bytes)", + int(build_stats["flash_used"]), + build_stats["flash_percent"], + int(build_stats["flash_max"]), + ) + if build_stats["flash_used"]: + logging.info( + "UI payload share: %.3f%% of compiled image (%d / %d bytes)", + (bytes_used / build_stats["flash_used"]) * 100.0, + bytes_used, + int(build_stats["flash_used"]), + ) + if build_stats.get("ram_used") is not None: + logging.info( + "Sketch RAM usage: %d bytes (%.2f%% of %d bytes)", + int(build_stats["ram_used"]), + build_stats["ram_percent"], + int(build_stats["ram_max"]), + ) + + if args.report_only: + return 0 + + handler = DriverStationHandler + + if args.suite: + servers: List[ThreadedHTTPServer] = [] + threads: List[threading.Thread] = [] + try: + for idx, html_path in enumerate(html_variants): + port = args.suite_base_port + idx + httpd = ThreadedHTTPServer(("", port), handler, html_override=html_path) + thread = threading.Thread(target=httpd.serve_forever, daemon=True) + thread.start() + servers.append(httpd) + threads.append(thread) + logging.info("Serving %s at http://localhost:%d/", html_path.name, port) + logging.info("Press Ctrl+C to stop all servers.") + while True: + time.sleep(1) + except KeyboardInterrupt: + logging.info("Stopping suite servers...") + finally: + for httpd in servers: + httpd.shutdown() + for thread in threads: + thread.join(timeout=1) + return 0 + + html_override = html_variants[0] + with ThreadedHTTPServer(("", args.port), handler, html_override=html_override) as httpd: + url = f"http://localhost:{args.port}/" + logging.info("Serving driver station UI at %s", url) + + if args.open_browser: + try: + import webbrowser + + webbrowser.open(url) + except Exception as exc: # pragma: no cover - guard rail + logging.warning("Failed to open browser: %s", exc) + + try: + httpd.serve_forever() + except KeyboardInterrupt: + logging.info("Shutting down simulator.") + httpd.shutdown() + + return 0 + + +if __name__ == "__main__": # pragma: no cover + sys.exit(main(sys.argv[1:])) diff --git a/ui-testing/variants/aero_hud.html b/ui-testing/variants/aero_hud.html new file mode 100644 index 0000000..32b1e9f --- /dev/null +++ b/ui-testing/variants/aero_hud.html @@ -0,0 +1,398 @@ + + + + + ProBot Flight HUD + + + +
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/base.html b/ui-testing/variants/base.html new file mode 100644 index 0000000..8d32759 --- /dev/null +++ b/ui-testing/variants/base.html @@ -0,0 +1,67 @@ + + + + + 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/circuit_glow.html b/ui-testing/variants/circuit_glow.html new file mode 100644 index 0000000..f4987c0 --- /dev/null +++ b/ui-testing/variants/circuit_glow.html @@ -0,0 +1,365 @@ + + + + + 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/command_deck.html b/ui-testing/variants/command_deck.html new file mode 100644 index 0000000..7ca4239 --- /dev/null +++ b/ui-testing/variants/command_deck.html @@ -0,0 +1,430 @@ + + + + + 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/control_tower.html b/ui-testing/variants/control_tower.html new file mode 100644 index 0000000..0ed02c9 --- /dev/null +++ b/ui-testing/variants/control_tower.html @@ -0,0 +1,352 @@ + + + + + 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/minimal_stack.html b/ui-testing/variants/minimal_stack.html new file mode 100644 index 0000000..a165268 --- /dev/null +++ b/ui-testing/variants/minimal_stack.html @@ -0,0 +1,367 @@ + + + + + ProBot Minimal Stack + + + +
+
+

ProBot Minimal Stack

+ Clean command surface +
+
Standby
+
+
+
+

Match Control

+
+ +
+ + + Seconds +
+
+ Autonomous + +
+
+ +
+ Joystick: Not Connected +
+
+
+

Joystick Telemetry

+ +
No gamepad selected.
+
No axis data...
+
No button data...
+
+
+ + + diff --git a/ui-testing/variants/neon_grid.html b/ui-testing/variants/neon_grid.html new file mode 100644 index 0000000..40d803b --- /dev/null +++ b/ui-testing/variants/neon_grid.html @@ -0,0 +1,356 @@ + + + + + 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/pit_wall.html b/ui-testing/variants/pit_wall.html new file mode 100644 index 0000000..10ebd72 --- /dev/null +++ b/ui-testing/variants/pit_wall.html @@ -0,0 +1,412 @@ + + + + + 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/retro_terminal.html b/ui-testing/variants/retro_terminal.html new file mode 100644 index 0000000..e2ba12a --- /dev/null +++ b/ui-testing/variants/retro_terminal.html @@ -0,0 +1,287 @@ + + + + + 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/zen_flow.html b/ui-testing/variants/zen_flow.html new file mode 100644 index 0000000..ccaf730 --- /dev/null +++ b/ui-testing/variants/zen_flow.html @@ -0,0 +1,359 @@ + + + + + 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...
+
+
+ + + From 9bd411881e4d594e2f5f450dc756d41b8c5b32d7 Mon Sep 17 00:00:00 2001 From: tunapro Date: Thu, 16 Oct 2025 19:39:15 +0300 Subject: [PATCH 04/26] feat(ui-testing): add variant suite and minimal stack enhancements --- ui-testing/README.md | 12 +- .../variants/{ => archive}/aero_hud.html | 0 ui-testing/variants/{ => archive}/base.html | 0 .../variants/{ => archive}/circuit_glow.html | 0 .../variants/{ => archive}/control_tower.html | 0 .../variants/{ => archive}/neon_grid.html | 0 .../{ => archive}/retro_terminal.html | 0 .../variants/{ => archive}/zen_flow.html | 0 ui-testing/variants/command_deck.html | 238 ++++++++-- ui-testing/variants/minimal_stack.html | 410 +++++++++++++++++- ui-testing/variants/pit_wall.html | 21 + 11 files changed, 614 insertions(+), 67 deletions(-) rename ui-testing/variants/{ => archive}/aero_hud.html (100%) rename ui-testing/variants/{ => archive}/base.html (100%) rename ui-testing/variants/{ => archive}/circuit_glow.html (100%) rename ui-testing/variants/{ => archive}/control_tower.html (100%) rename ui-testing/variants/{ => archive}/neon_grid.html (100%) rename ui-testing/variants/{ => archive}/retro_terminal.html (100%) rename ui-testing/variants/{ => archive}/zen_flow.html (100%) diff --git a/ui-testing/README.md b/ui-testing/README.md index 8b48778..0a295c2 100644 --- a/ui-testing/README.md +++ b/ui-testing/README.md @@ -41,12 +41,12 @@ python3 ui-testing/server.py --report-only --build-report ## Varyasyonlarla Çalışma -- `ui-testing/variants/` klasöründe mevcut arayüzün birebir kopyası (`base.html`) - ve dokuz farklı konsept örneği bulunuyor: - `command_deck.html`, `aero_hud.html`, `pit_wall.html`, `minimal_stack.html`, - `retro_terminal.html`, `neon_grid.html`, `control_tower.html`, - `zen_flow.html`, `circuit_glow.html`. Yeni tasarımlar için bu dosyaları - başlangıç noktası olarak kopyalayıp düzenleyebilirsiniz. +- `ui-testing/variants/` klasöründe aktif olarak denediğimiz üç tasarım + (`command_deck.html`, `minimal_stack.html`, `pit_wall.html`) bulunuyor. +- Diğer örnekler (`aero_hud.html`, `base.html`, `circuit_glow.html`, + `control_tower.html`, `neon_grid.html`, `retro_terminal.html`, `zen_flow.html`) + `ui-testing/variants/archive/` altına taşındı; referans olarak saklayabilir + ya da tekrar aktive etmek için bu klasörden çıkarabilirsiniz. - Seçili bir varyasyonu denemek için: ```bash diff --git a/ui-testing/variants/aero_hud.html b/ui-testing/variants/archive/aero_hud.html similarity index 100% rename from ui-testing/variants/aero_hud.html rename to ui-testing/variants/archive/aero_hud.html diff --git a/ui-testing/variants/base.html b/ui-testing/variants/archive/base.html similarity index 100% rename from ui-testing/variants/base.html rename to ui-testing/variants/archive/base.html diff --git a/ui-testing/variants/circuit_glow.html b/ui-testing/variants/archive/circuit_glow.html similarity index 100% rename from ui-testing/variants/circuit_glow.html rename to ui-testing/variants/archive/circuit_glow.html diff --git a/ui-testing/variants/control_tower.html b/ui-testing/variants/archive/control_tower.html similarity index 100% rename from ui-testing/variants/control_tower.html rename to ui-testing/variants/archive/control_tower.html diff --git a/ui-testing/variants/neon_grid.html b/ui-testing/variants/archive/neon_grid.html similarity index 100% rename from ui-testing/variants/neon_grid.html rename to ui-testing/variants/archive/neon_grid.html diff --git a/ui-testing/variants/retro_terminal.html b/ui-testing/variants/archive/retro_terminal.html similarity index 100% rename from ui-testing/variants/retro_terminal.html rename to ui-testing/variants/archive/retro_terminal.html diff --git a/ui-testing/variants/zen_flow.html b/ui-testing/variants/archive/zen_flow.html similarity index 100% rename from ui-testing/variants/zen_flow.html rename to ui-testing/variants/archive/zen_flow.html diff --git a/ui-testing/variants/command_deck.html b/ui-testing/variants/command_deck.html index 7ca4239..7af7698 100644 --- a/ui-testing/variants/command_deck.html +++ b/ui-testing/variants/command_deck.html @@ -11,40 +11,135 @@ --accent-soft:rgba(255,140,55,0.16); --panel:#032b63; --outline:rgba(229,228,226,0.25); + --bg-main:linear-gradient(135deg,#00132d 0%,#032b63 70%,#073c85 100%); + --text-color:var(--ice); + --header-bg:rgba(0,8,25,0.82); + --header-border:var(--outline); + --nav-link-color:var(--ice); + --nav-link-hover:#ffffff; + --card-bg:linear-gradient(160deg,rgba(3,43,99,0.95),rgba(0,15,40,0.9)); + --card-shadow:0 18px 26px rgba(0,0,0,0.28); + --panel-border:var(--outline); + --control-bg:rgba(255,255,255,0.05); + --input-bg:rgba(0,15,40,0.6); + --input-border:rgba(255,255,255,0.2); + --data-bg:rgba(255,255,255,0.03); + --badge-bg:var(--accent-soft); + --badge-text:var(--accent); + --btn-init-bg:#e5e4e2; + --btn-init-color:#00204d; + --btn-start-bg:#20ff8f; + --btn-start-color:#012339; + --btn-stop-bg:#ff5555; + --btn-stop-color:#ffffff; font-family:"Segoe UI",Roboto,system-ui,-apple-system,sans-serif; } + body[data-theme="light"]{ + --bg-main:linear-gradient(180deg,#ffffff 0%,#f3f7ff 55%,#e3ecfb 100%); + --text-color:#1a2b4d; + --header-bg:rgba(248,250,255,0.96); + --header-border:rgba(0,32,77,0.08); + --nav-link-color:#324d74; + --nav-link-hover:#00204d; + --card-bg:#ffffff; + --card-shadow:0 30px 46px rgba(0,32,77,0.16),0 10px 18px rgba(0,32,77,0.08); + --panel-border:rgba(0,32,77,0.12); + --control-bg:linear-gradient(180deg,rgba(255,255,255,0.96),rgba(235,242,255,0.86)); + --input-bg:rgba(255,255,255,0.95); + --input-border:rgba(0,32,77,0.2); + --data-bg:rgba(0,32,77,0.05); + --badge-bg:rgba(255,140,55,0.2); + --badge-text:#c65f1f; + } *{box-sizing:border-box;margin:0;padding:0;} body{ - background:linear-gradient(135deg,#00132d 0%,#032b63 70%,#073c85 100%); - color:var(--ice); + background:var(--bg-main); + color:var(--text-color); min-height:100vh; display:flex; flex-direction:column; + transition:background 240ms ease,color 240ms ease; } header{ display:flex; justify-content:space-between; align-items:center; padding:18px 32px; - background:rgba(0,8,25,0.72); + background:var(--header-bg); backdrop-filter:blur(9px); - border-bottom:1px solid var(--outline); + border-bottom:1px solid var(--header-border); position:sticky; top:0; z-index:10; + gap:32px; } header h1{ font-size:1.6rem; letter-spacing:0.08em; text-transform:uppercase; } + header nav{ + display:flex; + gap:20px; + margin-left:auto; + } + header nav a{ + color:var(--nav-link-color); + text-decoration:none; + letter-spacing:0.14em; + font-size:0.78rem; + text-transform:uppercase; + opacity:0.75; + transition:opacity 120ms ease; + } + header nav a:hover{opacity:1;color:var(--nav-link-hover);} header .badge{ - background:var(--accent-soft); - color:var(--accent); + background:var(--badge-bg); + color:var(--badge-text); padding:6px 12px; border-radius:999px; font-size:0.8rem; letter-spacing:0.12em; + transition:background 160ms ease, color 160ms ease, box-shadow 160ms ease; + } + header .badge[data-phase="init"]{ + background:linear-gradient(120deg,rgba(255,140,55,0.35),rgba(255,140,55,0.18)); + color:#ffe0c6; + box-shadow:0 0 12px rgba(255,140,55,0.4); + } + header .badge[data-phase="start"]{ + background:linear-gradient(120deg,rgba(32,255,143,0.35),rgba(32,255,143,0.18)); + color:#d8ffee; + box-shadow:0 0 12px rgba(32,255,143,0.35); + } + header .badge[data-phase="stop"]{ + background:linear-gradient(120deg,rgba(255,85,85,0.35),rgba(255,85,85,0.18)); + color:#ffe4e4; + box-shadow:0 0 12px rgba(255,85,85,0.4); + } + body[data-theme="light"] header .badge[data-phase]{ + color:#00204d; + } + body[data-theme="light"] header{ + box-shadow:0 18px 32px rgba(0,32,77,0.16); + } + body[data-theme="light"] .card{ + border-color:rgba(0,32,77,0.08); + } + body[data-theme="light"] .status-chip{ + background:rgba(0,32,77,0.08); + color:#1a2b4d; + } + body[data-theme="light"] .control-toggle{ + box-shadow:0 16px 28px rgba(0,32,77,0.12); + border-color:rgba(0,32,77,0.1); + } + body[data-theme="light"] .data-block{ + border-color:rgba(0,32,77,0.1); + box-shadow:inset 0 1px 3px rgba(0,32,77,0.09); + } + body[data-theme="light"] button{ + box-shadow:0 22px 32px rgba(0,32,77,0.18); } main{ flex:1; @@ -54,11 +149,12 @@ gap:24px; } .card{ - background:linear-gradient(160deg,rgba(3,43,99,0.95),rgba(0,15,40,0.9)); - border:1px solid var(--outline); + background:var(--card-bg); + border:1px solid var(--panel-border); border-radius:18px; padding:24px; - box-shadow:0 18px 26px rgba(0,0,0,0.28); + box-shadow:var(--card-shadow); + transition:background 180ms ease,box-shadow 180ms ease,border-color 180ms ease; } .card h2{ font-size:1rem; @@ -107,20 +203,41 @@ letter-spacing:0.12em; cursor:pointer; transition:transform 120ms ease,box-shadow 120ms ease,background 200ms ease; - color:var(--navy); - background:var(--ice); - box-shadow:0 14px 22px rgba(0,0,0,0.25); + box-shadow:0 14px 22px rgba(0,0,0,0.18); } button:hover{transform:translateY(-3px);} button:active{transform:translateY(1px);box-shadow:0 8px 12px rgba(0,0,0,0.22);} + .state-init{ + background:var(--btn-init-bg); + color:var(--btn-init-color); + } + .state-start{ + background:var(--btn-start-bg); + color:var(--btn-start-color); + } + .state-stop{ + background:var(--btn-stop-bg); + color:var(--btn-stop-color); + } + body[data-theme="light"] .state-init{ + background:linear-gradient(180deg,#ffffff 0%,#f3f6ff 100%); + } + body[data-theme="light"] .state-start{ + background:linear-gradient(180deg,#20ffaf 0%,#5dffd3 100%); + } + body[data-theme="light"] .state-stop{ + background:linear-gradient(180deg,#ff6a6a 0%,#ff9191 100%); + color:#4a0f0f; + } .control-toggle{ display:flex; align-items:center; justify-content:space-between; padding:12px 16px; border-radius:12px; - background:rgba(255,255,255,0.05); - border:1px solid var(--outline); + background:var(--control-bg); + border:1px solid var(--panel-border); + transition:background 180ms ease,box-shadow 180ms ease,border-color 180ms ease; } .control-toggle label{ display:flex; @@ -133,9 +250,9 @@ width:70px; padding:6px 8px; border-radius:8px; - border:1px solid rgba(255,255,255,0.2); - background:rgba(0,15,40,0.6); - color:var(--ice); + border:1px solid var(--input-border); + background:var(--input-bg); + color:var(--text-color); text-align:center; } .switch{ @@ -182,28 +299,51 @@ gap:16px; } .data-block{ - background:rgba(255,255,255,0.03); - border:1px solid var(--outline); + background:var(--data-bg); + border:1px solid var(--panel-border); border-radius:12px; padding:16px; max-height:200px; overflow:auto; font-family:"SFMono-Regular","Roboto Mono",monospace; font-size:0.85rem; + transition:background 180ms ease,border-color 180ms ease,box-shadow 180ms ease; } select{ width:100%; padding:12px; border-radius:10px; - border:1px solid rgba(255,255,255,0.26); - background:rgba(0,15,40,0.7); - color:var(--ice); + border:1px solid var(--panel-border); + background:var(--input-bg); + color:var(--text-color); } .hint{ font-size:0.78rem; opacity:0.7; margin-top:4px; } + .theme-toggle{ + border:1px solid rgba(255,255,255,0.25); + background:transparent; + color:var(--nav-link-color); + padding:8px 16px; + border-radius:999px; + letter-spacing:0.12em; + font-size:0.75rem; + text-transform:uppercase; + cursor:pointer; + transition:background 140ms ease,color 140ms ease; + } + .theme-toggle:hover{ + background:rgba(255,255,255,0.12); + } + body[data-theme="light"] .theme-toggle{ + border:1px solid rgba(0,32,77,0.16); + } + body[data-theme="light"] .theme-toggle:hover{ + background:rgba(0,32,77,0.08); + color:#00204d; + } @media (max-width:720px){ header{padding:14px 20px;} main{padding:20px;} @@ -213,9 +353,15 @@ } - +

ProBot Command Deck

+ +
Phase: Standby
@@ -229,7 +375,7 @@

00:30
- +
+
+
+

Telemetry Log

@@ -227,18 +481,99 @@

Joystick Telemetry

No axis data...
No button data...
-
+ + diff --git a/ui-testing/variants/pit_wall.html b/ui-testing/variants/pit_wall.html index 10ebd72..02cf174 100644 --- a/ui-testing/variants/pit_wall.html +++ b/ui-testing/variants/pit_wall.html @@ -27,12 +27,28 @@ align-items:center; border-bottom:1px solid rgba(229,228,226,0.12); background:linear-gradient(180deg,rgba(0,11,30,0.95),rgba(0,11,30,0.7)); + gap:24px; } header h1{ text-transform:uppercase; letter-spacing:0.16em; font-size:1.4rem; } + header nav{ + display:flex; + gap:18px; + margin-left:auto; + } + header nav a{ + color:rgba(229,228,226,0.85); + text-decoration:none; + letter-spacing:0.14em; + font-size:0.78rem; + text-transform:uppercase; + opacity:0.75; + transition:opacity 120ms ease; + } + header nav a:hover{opacity:1;} .status-strip{ display:flex; gap:18px; @@ -214,6 +230,11 @@

ProBot Pit Wall

+
PHASE From c356bf3b3239072074aa6a7888539d316ac05201 Mon Sep 17 00:00:00 2001 From: tunapro Date: Thu, 16 Oct 2025 20:03:53 +0300 Subject: [PATCH 05/26] style(ui-testing): balance minimal stack layout --- ui-testing/variants/minimal_stack.html | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/ui-testing/variants/minimal_stack.html b/ui-testing/variants/minimal_stack.html index 703e480..c0ae58d 100644 --- a/ui-testing/variants/minimal_stack.html +++ b/ui-testing/variants/minimal_stack.html @@ -65,13 +65,14 @@ box-shadow:0 -24px 48px rgba(0,32,77,0.12); padding:36px 48px; display:grid; - grid-template-columns:1.2fr 1fr; + grid-template-columns:minmax(0,1fr) minmax(0,1fr); gap:36px; } .column{ display:flex; flex-direction:column; gap:32px; + min-width:0; } .stack-card{ background:#fff; @@ -399,6 +400,8 @@ background:#f7f9ff; font-family:"SFMono-Regular","Roboto Mono",monospace; line-height:1.5; + white-space:pre-wrap; + word-break:break-word; } .hint{ font-size:0.78rem; From 0eb0f524967c827707cd8e95854e690baa67d8b0 Mon Sep 17 00:00:00 2001 From: tunapro Date: Thu, 16 Oct 2025 22:58:09 +0300 Subject: [PATCH 06/26] fix(ui-testing): adjust state machine transitions --- ui-testing/variants/minimal_stack.html | 74 +++++++++++++++++--------- 1 file changed, 48 insertions(+), 26 deletions(-) diff --git a/ui-testing/variants/minimal_stack.html b/ui-testing/variants/minimal_stack.html index c0ae58d..693da20 100644 --- a/ui-testing/variants/minimal_stack.html +++ b/ui-testing/variants/minimal_stack.html @@ -487,23 +487,30 @@

Telemetry Log

+ From ad5377ff32bf8e24cd4c250356818a1dd92f74a9 Mon Sep 17 00:00:00 2001 From: tunapro Date: Fri, 17 Oct 2025 15:54:44 +0300 Subject: [PATCH 10/26] Tune portrait header behavior --- ui-testing/variants/minimal_stack.html | 66 +++++++++++++++++++------- 1 file changed, 48 insertions(+), 18 deletions(-) diff --git a/ui-testing/variants/minimal_stack.html b/ui-testing/variants/minimal_stack.html index 24dc098..33e86b2 100644 --- a/ui-testing/variants/minimal_stack.html +++ b/ui-testing/variants/minimal_stack.html @@ -117,6 +117,27 @@ .app-header.compact .header-status .status-detail{ display:none; } + + @media(max-width:900px){ + .app-header.compact{ + padding:18px 24px; + } + .app-header.compact .header-left h1{ + display:none; + } + .app-header.compact .header-left .header-subtitle{ + display:none; + } + .app-header.compact nav{ + gap:12px; + } + .app-header.compact nav a{ + font-size:0.98rem; + } + .app-header.compact .header-status{ + display:none; + } + } .app-header.force-compact{ padding:6px 18px; gap:12px; @@ -159,10 +180,10 @@ scroll-margin-top:120px; } .stack-card h2{ - font-size:1rem; - letter-spacing:0.16em; + font-size:1.1rem; + letter-spacing:0.12em; text-transform:uppercase; - color:#3b4c68; + color:#233351; } .control-row{ display:grid; @@ -483,16 +504,7 @@ letter-spacing:0.09em; } .app-header .header-status{ - order:2; - width:100%; - align-items:flex-start; - gap:4px; - } - .app-header .header-status .status-value{ - font-size:0.92rem; - } - .app-header .header-status .status-detail{ - font-size:0.72rem; + display:none; } .stack-card h2{ font-size:1.2rem; @@ -520,7 +532,7 @@ gap:18px; } .app-header nav a{ - font-size:1.2rem; + font-size:1.15rem; letter-spacing:0.08em; } .app-header .header-left{ @@ -535,10 +547,23 @@ font-size:1.3rem; letter-spacing:0.08em; } - .app-header .header-status{ - order:2; - width:100%; - align-items:flex-start; + .app-header.compact{ + padding:18px 32px; + } + .app-header.compact .header-left h1{ + display:none; + } + .app-header.compact .header-left .header-subtitle{ + display:none; + } + .app-header.compact nav{ + gap:18px; + } + .app-header.compact nav a{ + font-size:1.15rem; + } + .app-header.compact .header-status{ + display:none; } body{ font-size:1.9rem; @@ -747,6 +772,11 @@

Telemetry Log

headerEl.classList.remove('compact'); return; } + const isNarrowPortrait = window.innerWidth <= 900 && !landscapeQuery.matches; + if(isNarrowPortrait){ + headerEl.classList.remove('compact'); + return; + } const shouldCompact=window.scrollY>32; headerEl.classList.toggle('compact', shouldCompact); } From aa1f78addfc8932e54be904fbbd01a27992190c9 Mon Sep 17 00:00:00 2001 From: tunapro Date: Fri, 17 Oct 2025 16:19:28 +0300 Subject: [PATCH 11/26] Force compact header on portrait --- ui-testing/variants/minimal_stack.html | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ui-testing/variants/minimal_stack.html b/ui-testing/variants/minimal_stack.html index 33e86b2..f3f0247 100644 --- a/ui-testing/variants/minimal_stack.html +++ b/ui-testing/variants/minimal_stack.html @@ -1051,4 +1051,4 @@

Telemetry Log

}); - + \ No newline at end of file From c252ff2fdf40346fe6fbf7fa68be0b2381c01a4d Mon Sep 17 00:00:00 2001 From: tunapro Date: Fri, 17 Oct 2025 16:22:35 +0300 Subject: [PATCH 12/26] Keep compact header in portrait --- ui-testing/variants/minimal_stack.html | 29 +++++++++++++++----------- 1 file changed, 17 insertions(+), 12 deletions(-) diff --git a/ui-testing/variants/minimal_stack.html b/ui-testing/variants/minimal_stack.html index f3f0247..3661656 100644 --- a/ui-testing/variants/minimal_stack.html +++ b/ui-testing/variants/minimal_stack.html @@ -763,22 +763,22 @@

Telemetry Log

const headerStatusValue=document.getElementById('headerStatusValue'); const headerStatusDetail=document.getElementById('headerStatusDetail'); const landscapeQuery=window.matchMedia('(orientation:landscape)'); + const portraitQuery=window.matchMedia('(orientation:portrait)'); function applyHeaderMode(){ if(!headerEl) return; - const forceCompact=window.innerWidth<=1024 && landscapeQuery.matches; - headerEl.classList.toggle('force-compact', forceCompact); - if(forceCompact){ - headerEl.classList.remove('compact'); - return; + const landscapeCompact=landscapeQuery.matches && window.innerWidth<=1024; + const portraitCompact=portraitQuery.matches; + if(landscapeCompact){ + headerEl.classList.add('force-compact'); + }else{ + headerEl.classList.remove('force-compact'); } - const isNarrowPortrait = window.innerWidth <= 900 && !landscapeQuery.matches; - if(isNarrowPortrait){ - headerEl.classList.remove('compact'); - return; + if(portraitCompact || landscapeCompact){ + headerEl.classList.add('compact'); + }else{ + headerEl.classList.toggle('compact', window.scrollY>32); } - const shouldCompact=window.scrollY>32; - headerEl.classList.toggle('compact', shouldCompact); } window.addEventListener('scroll', applyHeaderMode, {passive:true}); @@ -788,6 +788,11 @@

Telemetry Log

}else if(typeof landscapeQuery.addListener === 'function'){ landscapeQuery.addListener(applyHeaderMode); } +if(typeof portraitQuery.addEventListener === 'function'){ + portraitQuery.addEventListener('change', applyHeaderMode); +}else if(typeof portraitQuery.addListener === 'function'){ + portraitQuery.addListener(applyHeaderMode); +} applyHeaderMode(); function setPhaseDisplay(mode){ @@ -1051,4 +1056,4 @@

Telemetry Log

}); - \ No newline at end of file + From 98e114af53abb4a1aac99c4c4564e0e84ffcdcb1 Mon Sep 17 00:00:00 2001 From: tunapro Date: Fri, 17 Oct 2025 16:36:42 +0300 Subject: [PATCH 13/26] Always use compact header --- ui-testing/variants/minimal_stack.html | 8 ++------ 1 file changed, 2 insertions(+), 6 deletions(-) diff --git a/ui-testing/variants/minimal_stack.html b/ui-testing/variants/minimal_stack.html index 3661656..b068936 100644 --- a/ui-testing/variants/minimal_stack.html +++ b/ui-testing/variants/minimal_stack.html @@ -769,16 +769,12 @@

Telemetry Log

if(!headerEl) return; const landscapeCompact=landscapeQuery.matches && window.innerWidth<=1024; const portraitCompact=portraitQuery.matches; - if(landscapeCompact){ + headerEl.classList.add('compact'); + if(landscapeCompact || portraitCompact){ headerEl.classList.add('force-compact'); }else{ headerEl.classList.remove('force-compact'); } - if(portraitCompact || landscapeCompact){ - headerEl.classList.add('compact'); - }else{ - headerEl.classList.toggle('compact', window.scrollY>32); - } } window.addEventListener('scroll', applyHeaderMode, {passive:true}); From 4c4123515c3c8c50319f933c0339dfa3117525c9 Mon Sep 17 00:00:00 2001 From: tunapro Date: Fri, 17 Oct 2025 16:44:30 +0300 Subject: [PATCH 14/26] Simplify compact header styling --- ui-testing/variants/minimal_stack.html | 160 +++++++------------------ 1 file changed, 42 insertions(+), 118 deletions(-) diff --git a/ui-testing/variants/minimal_stack.html b/ui-testing/variants/minimal_stack.html index b068936..ac6cad1 100644 --- a/ui-testing/variants/minimal_stack.html +++ b/ui-testing/variants/minimal_stack.html @@ -24,43 +24,42 @@ position:sticky; top:0; z-index:100; - padding:24px 48px; + padding:16px 28px; display:flex; align-items:center; - gap:24px; + gap:16px; justify-content:space-between; background:var(--navy); color:var(--ice); - box-shadow:0 10px 24px rgba(0,32,77,0.28); + box-shadow:0 8px 18px rgba(0,32,77,0.24); border-bottom:1px solid rgba(229,228,226,0.12); - transition:padding 180ms ease, box-shadow 180ms ease; } .app-header .header-left{ display:flex; flex-direction:column; - gap:6px; + gap:4px; } .app-header .header-left h1{ - font-size:2.1rem; - letter-spacing:0.06em; + font-size:1.5rem; + letter-spacing:0.08em; } .app-header .header-left .header-subtitle{ - font-size:1rem; - color:rgba(229,228,226,0.75); + font-size:0.82rem; + color:rgba(229,228,226,0.8); text-transform:uppercase; - letter-spacing:0.1em; + letter-spacing:0.08em; } .app-header nav{ display:flex; - gap:20px; + gap:16px; flex:1; justify-content:center; } .app-header nav a{ color:var(--ice); text-decoration:none; - letter-spacing:0.12em; - font-size:0.9rem; + letter-spacing:0.1em; + font-size:0.85rem; text-transform:uppercase; opacity:0.82; transition:opacity 120ms ease; @@ -68,91 +67,55 @@ .app-header nav a:hover{opacity:1;} .app-header .header-status{ display:flex; - flex-direction:column; - align-items:flex-end; - gap:4px; + flex-direction:row; + align-items:center; + gap:6px; text-transform:uppercase; letter-spacing:0.16em; } .app-header .header-status .status-label{ - font-size:0.68rem; - letter-spacing:0.24em; + font-size:0.6rem; + letter-spacing:0.2em; opacity:0.7; } .app-header .header-status .status-value{ - font-size:1.05rem; - letter-spacing:0.16em; + font-size:0.9rem; + letter-spacing:0.14em; } .app-header .header-status .status-detail{ - font-size:0.78rem; - letter-spacing:0.12em; - opacity:0.75; - } - .app-header.compact{ - padding:8px 24px; - box-shadow:0 8px 18px rgba(0,32,77,0.24); - } - .app-header.compact .header-left h1{ - font-size:1.45rem; - } - .app-header.compact .header-left .header-subtitle{ - display:none; - } - .app-header.compact nav{ - gap:16px; - } - .app-header.compact nav a{ - font-size:0.85rem; - letter-spacing:0.1em; - } - .app-header.compact .header-status{ - flex-direction:row; - align-items:center; - gap:6px; - } - .app-header.compact .header-status .status-label{ - font-size:0.6rem; - letter-spacing:0.2em; - } - .app-header.compact .header-status .status-detail{ display:none; } @media(max-width:900px){ - .app-header.compact{ + .app-header{ + flex-direction:column; + align-items:flex-start; + gap:12px; padding:18px 24px; } - .app-header.compact .header-left h1{ + .app-header .header-left{ + width:100%; + } + .app-header .header-left h1{ display:none; } - .app-header.compact .header-left .header-subtitle{ + .app-header .header-left .header-subtitle{ display:none; } - .app-header.compact nav{ + .app-header nav{ + order:3; + width:100%; + flex-wrap:wrap; + justify-content:space-between; gap:12px; } - .app-header.compact nav a{ + .app-header nav a{ font-size:0.98rem; } - .app-header.compact .header-status{ + .app-header .header-status{ display:none; } } - .app-header.force-compact{ - padding:6px 18px; - gap:12px; - } - .app-header.force-compact nav{ - gap:12px; - } - .app-header.force-compact nav a{ - font-size:0.78rem; - letter-spacing:0.14em; - } - .app-header.force-compact .header-status, - .app-header.force-compact .header-left{ - display:none; - } main{ flex:1; background:linear-gradient(180deg,#ffffff 0%,#f3f7ff 70%,#e7eefb 100%); @@ -520,8 +483,8 @@ .app-header{ flex-direction:column; align-items:flex-start; - gap:18px; - padding:28px 32px; + gap:16px; + padding:18px 24px; justify-content:flex-start; } .app-header nav{ @@ -536,33 +499,22 @@ letter-spacing:0.08em; } .app-header .header-left{ - gap:8px; + gap:6px; width:100%; } .app-header .header-left h1{ - font-size:3rem; - letter-spacing:0.05em; - } - .app-header .header-left .header-subtitle{ - font-size:1.3rem; - letter-spacing:0.08em; - } - .app-header.compact{ - padding:18px 32px; - } - .app-header.compact .header-left h1{ display:none; } - .app-header.compact .header-left .header-subtitle{ + .app-header .header-left .header-subtitle{ display:none; } - .app-header.compact nav{ + .app-header nav{ gap:18px; } - .app-header.compact nav a{ + .app-header nav a{ font-size:1.15rem; } - .app-header.compact .header-status{ + .app-header .header-status{ display:none; } body{ @@ -762,34 +714,6 @@

Telemetry Log

const headerEl=document.getElementById('appHeader'); const headerStatusValue=document.getElementById('headerStatusValue'); const headerStatusDetail=document.getElementById('headerStatusDetail'); - const landscapeQuery=window.matchMedia('(orientation:landscape)'); - const portraitQuery=window.matchMedia('(orientation:portrait)'); - -function applyHeaderMode(){ - if(!headerEl) return; - const landscapeCompact=landscapeQuery.matches && window.innerWidth<=1024; - const portraitCompact=portraitQuery.matches; - headerEl.classList.add('compact'); - if(landscapeCompact || portraitCompact){ - headerEl.classList.add('force-compact'); - }else{ - headerEl.classList.remove('force-compact'); - } -} - -window.addEventListener('scroll', applyHeaderMode, {passive:true}); -window.addEventListener('resize', applyHeaderMode); -if(typeof landscapeQuery.addEventListener === 'function'){ - landscapeQuery.addEventListener('change', applyHeaderMode); -}else if(typeof landscapeQuery.addListener === 'function'){ - landscapeQuery.addListener(applyHeaderMode); -} -if(typeof portraitQuery.addEventListener === 'function'){ - portraitQuery.addEventListener('change', applyHeaderMode); -}else if(typeof portraitQuery.addListener === 'function'){ - portraitQuery.addListener(applyHeaderMode); -} -applyHeaderMode(); function setPhaseDisplay(mode){ const map={ From f882fb06c685771c063bfbd209eb272e8e725c51 Mon Sep 17 00:00:00 2001 From: tunapro Date: Sat, 18 Oct 2025 01:18:49 +0300 Subject: [PATCH 15/26] Refine minimal UI theme and archive unused variants --- ui-testing/README.md | 13 ++-- .../variants/{ => archive}/command_deck.html | 42 +++++++++++- .../variants/{ => archive}/pit_wall.html | 0 ui-testing/variants/minimal_stack.html | 68 ++++++++++--------- 4 files changed, 83 insertions(+), 40 deletions(-) rename ui-testing/variants/{ => archive}/command_deck.html (95%) rename ui-testing/variants/{ => archive}/pit_wall.html (100%) diff --git a/ui-testing/README.md b/ui-testing/README.md index 0a295c2..d226192 100644 --- a/ui-testing/README.md +++ b/ui-testing/README.md @@ -41,12 +41,13 @@ python3 ui-testing/server.py --report-only --build-report ## Varyasyonlarla Çalışma -- `ui-testing/variants/` klasöründe aktif olarak denediğimiz üç tasarım - (`command_deck.html`, `minimal_stack.html`, `pit_wall.html`) bulunuyor. -- Diğer örnekler (`aero_hud.html`, `base.html`, `circuit_glow.html`, - `control_tower.html`, `neon_grid.html`, `retro_terminal.html`, `zen_flow.html`) - `ui-testing/variants/archive/` altına taşındı; referans olarak saklayabilir - ya da tekrar aktive etmek için bu klasörden çıkarabilirsiniz. +- `ui-testing/variants/` klasöründe artık temel arayüz olarak yalnızca + `minimal_stack.html` bulunur. +- Diğer örnekler (önceki `command_deck.html` ve `pit_wall.html` dahil olmak + üzere `aero_hud.html`, `base.html`, `circuit_glow.html`, `control_tower.html`, + `neon_grid.html`, `retro_terminal.html`, `zen_flow.html`) referans olarak + `ui-testing/variants/archive/` altına taşındı; dilediğiniz zaman geri almak + için bu klasörden çıkarabilirsiniz. - Seçili bir varyasyonu denemek için: ```bash diff --git a/ui-testing/variants/command_deck.html b/ui-testing/variants/archive/command_deck.html similarity index 95% rename from ui-testing/variants/command_deck.html rename to ui-testing/variants/archive/command_deck.html index 7af7698..7ceda62 100644 --- a/ui-testing/variants/command_deck.html +++ b/ui-testing/variants/archive/command_deck.html @@ -344,13 +344,53 @@ background:rgba(0,32,77,0.08); color:#00204d; } + @media (max-width:900px){ + header{ + padding:12px 18px; + gap:18px; + } + header h1{font-size:1.2rem;} + header nav{gap:12px;} + header nav a{font-size:0.7rem;} + .theme-toggle{ + padding:6px 12px; + font-size:0.68rem; + } + .badge{ + padding:4px 10px; + font-size:0.7rem; + } + } @media (max-width:720px){ - header{padding:14px 20px;} + header{padding:10px 16px;} + header nav{display:none;} main{padding:20px;} .card{padding:20px;} .match-timer{font-size:2.2rem;} button{padding:14px;font-size:0.9rem;} } + @media (max-height:520px) and (orientation:landscape){ + header{ + padding:8px 16px; + gap:12px; + } + header h1{font-size:1.1rem;} + .theme-toggle{padding:5px 10px;} + .badge{ + padding:4px 8px; + font-size:0.65rem; + } + } + @media (max-width:900px) and (orientation:portrait){ + main{ + display:flex; + flex-direction:column; + gap:18px; + } + main > .card{ + max-width:100%; + } + } diff --git a/ui-testing/variants/pit_wall.html b/ui-testing/variants/archive/pit_wall.html similarity index 100% rename from ui-testing/variants/pit_wall.html rename to ui-testing/variants/archive/pit_wall.html diff --git a/ui-testing/variants/minimal_stack.html b/ui-testing/variants/minimal_stack.html index ac6cad1..9d31465 100644 --- a/ui-testing/variants/minimal_stack.html +++ b/ui-testing/variants/minimal_stack.html @@ -7,15 +7,14 @@ :root{ --navy:#00204d; --ice:#e5e4e2; - --ink:#0b1a33; - --sky:#5aa0ff; - --sand:#f5f1e6; + --start:#28a745; + --stop:#d93025; font-family:"Inter","Segoe UI",sans-serif; } *{margin:0;padding:0;box-sizing:border-box;} body{ min-height:100vh; - background:var(--sand); + background:var(--ice); color:var(--navy); display:flex; flex-direction:column; @@ -118,7 +117,7 @@ } main{ flex:1; - background:linear-gradient(180deg,#ffffff 0%,#f3f7ff 70%,#e7eefb 100%); + background:linear-gradient(180deg,var(--ice) 0%,rgba(229,228,226,0.85) 70%,rgba(229,228,226,0.7) 100%); box-shadow:0 -24px 48px rgba(0,32,77,0.12); padding:36px 48px 48px; display:grid; @@ -132,7 +131,7 @@ min-width:0; } .stack-card{ - background:#fff; + background:var(--ice); border-radius:24px; padding:28px; border:1px solid rgba(0,32,77,0.12); @@ -146,7 +145,7 @@ font-size:1.1rem; letter-spacing:0.12em; text-transform:uppercase; - color:#233351; + color:rgba(0,32,77,0.85); } .control-row{ display:grid; @@ -154,7 +153,7 @@ gap:16px; } .control{ - background:#f5f8ff; + background:rgba(229,228,226,0.9); border-radius:16px; padding:16px; border:1px solid rgba(0,32,77,0.08); @@ -165,13 +164,13 @@ .control label{ font-size:0.96rem; letter-spacing:0.08em; - color:#556787; + color:rgba(0,32,77,0.65); } .control input[type="number"]{ padding:10px; border-radius:12px; border:1px solid rgba(0,32,77,0.14); - background:#fff; + background:var(--ice); text-align:center; font-size:1rem; color:var(--navy); @@ -192,14 +191,14 @@ justify-content:space-between; align-items:center; font-size:0.95rem; - color:#35507a; + color:rgba(0,32,77,0.75); letter-spacing:0.08em; text-transform:uppercase; } .auto-progress-header strong{ font-size:1.25rem; letter-spacing:0.08em; - color:#0f2c56; + color:rgba(0,32,77,0.8); } .auto-progress-bar{ position:relative; @@ -214,7 +213,7 @@ top:0; bottom:0; width:0%; - background:linear-gradient(90deg,#5aa0ff,#6fe2ff); + background:linear-gradient(90deg,var(--navy),rgba(0,32,77,0.6)); border-radius:inherit; transition:width 120ms linear; } @@ -229,7 +228,7 @@ flex-direction:column; align-items:center; gap:8px; - color:#365279; + color:rgba(0,32,77,0.7); letter-spacing:0.08em; font-size:0.92rem; } @@ -238,7 +237,7 @@ width:120px; height:120px; border-radius:50%; - background:radial-gradient(circle,#ffffff 0%,#f2f6ff 65%,#dce6f8 100%); + background:radial-gradient(circle,var(--ice) 0%,rgba(229,228,226,0.85) 65%,rgba(229,228,226,0.7) 100%); box-shadow:inset 0 4px 12px rgba(0,32,77,0.12); } .joy-cross{ @@ -265,8 +264,8 @@ width:14px; height:14px; border-radius:50%; - background:#ff8c37; - box-shadow:0 0 10px rgba(255,140,55,0.4); + background:var(--navy); + box-shadow:0 0 10px rgba(0,32,77,0.4); transform:translate(-50%,-50%); left:50%; top:50%; @@ -281,9 +280,9 @@ width:48px; height:48px; border-radius:50%; - background:radial-gradient(circle at 30% 30%,rgba(255,255,255,0.85),rgba(197,214,241,0.7)); + background:radial-gradient(circle at 30% 30%,rgba(229,228,226,0.95),rgba(0,32,77,0.08)); border:1px solid rgba(0,32,77,0.18); - color:#1f3e65; + color:rgba(0,32,77,0.75); font-size:0.75rem; display:flex; align-items:center; @@ -302,10 +301,10 @@ justify-content:center; } .joy-button.active{ - background:radial-gradient(circle at 30% 30%,rgba(255,255,255,0.95),rgba(90,160,255,0.85)); - border-color:#386ecc; - color:#00204d; - box-shadow:0 10px 20px rgba(90,160,255,0.35),0 0 12px rgba(90,160,255,0.4); + background:radial-gradient(circle at 30% 30%,rgba(229,228,226,0.95),rgba(0,32,77,0.2)); + border-color:rgba(0,32,77,0.7); + color:var(--navy); + box-shadow:0 10px 20px rgba(0,32,77,0.35),0 0 12px rgba(0,32,77,0.3); transform:translateY(-2px); } .joy-status{ @@ -313,7 +312,7 @@ display:flex; flex-direction:column; gap:4px; - color:#2f4f73; + color:rgba(0,32,77,0.75); letter-spacing:0.06em; } .joy-status strong{ @@ -324,14 +323,14 @@ display:flex; align-items:center; justify-content:space-between; - background:#e8efff; + background:rgba(229,228,226,0.85); border-radius:16px; padding:10px 14px; } .switch span{ font-size:0.92rem; letter-spacing:0.1em; - color:#3b4c68; + color:rgba(0,32,77,0.7); } .switch input{ width:46px; @@ -351,7 +350,7 @@ position:absolute; top:2px; left:3px; - background:#fff; + background:var(--ice); box-shadow:0 6px 12px rgba(0,32,77,0.24); transition:transform 160ms ease; } @@ -387,7 +386,7 @@ padding:14px; border-radius:16px; border:1px solid rgba(0,32,77,0.12); - background:#fff; + background:var(--ice); font-size:1.05rem; color:var(--navy); letter-spacing:0.04em; @@ -395,7 +394,7 @@ .telemetry pre{ height:140px; overflow:auto; - background:#f7f9ff; + background:rgba(229,228,226,0.92); font-family:"SFMono-Regular","Roboto Mono",monospace; line-height:1.5; white-space:pre-wrap; @@ -403,7 +402,7 @@ } .hint{ font-size:0.88rem; - color:#6a7a93; + color:rgba(0,32,77,0.6); letter-spacing:0.06em; } @media(max-width:992px){ @@ -837,7 +836,8 @@

Telemetry Log

if(controlState==="idle"){ controlState="armed"; btn.textContent="Start"; - btn.style.background="#4aa96c"; + btn.style.background="var(--start)"; + btn.style.color="var(--ice)"; stopAutoTimer(); autoRemaining = autoLen; updateAutoDisplay(); @@ -845,7 +845,8 @@

Telemetry Log

}else if(controlState==="armed"){ controlState="running"; btn.textContent="Stop"; - btn.style.background="#d9534f"; + btn.style.background="var(--stop)"; + btn.style.color="var(--ice)"; if(enableAuto && autoLen>0){ startAutoTimer(autoLen); setPhaseDisplay('auto'); @@ -857,6 +858,7 @@

Telemetry Log

controlState="idle"; btn.textContent="Init"; btn.style.background=varGet("--navy"); + btn.style.color="var(--ice)"; stopAutoTimer(); setPhaseDisplay('stopped'); } @@ -940,7 +942,7 @@

Telemetry Log

function varGet(name){ return getComputedStyle(document.documentElement).getPropertyValue(name).trim()||varDefaults[name]; } - const varDefaults={"--navy":"#00204d"}; + const varDefaults={"--navy":"#00204d","--start":"#28a745","--stop":"#d93025","--ice":"#e5e4e2"}; window.addEventListener('gamepadconnected',()=>{ updateGamepads(); From 23231e64b192b493c70777339e62eed60d55d2c9 Mon Sep 17 00:00:00 2001 From: tunapro Date: Sat, 18 Oct 2025 09:18:42 +0300 Subject: [PATCH 16/26] Rename driver station UI title --- ui-testing/variants/minimal_stack.html | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ui-testing/variants/minimal_stack.html b/ui-testing/variants/minimal_stack.html index 9d31465..2afd92d 100644 --- a/ui-testing/variants/minimal_stack.html +++ b/ui-testing/variants/minimal_stack.html @@ -2,7 +2,7 @@ - ProBot Minimal Stack + ProBot Driver Station - -
-
-

Main Drive

-

Joystick Status: Not Connected

- -

-

-

+
+
+

ProBot DriveStation

+ by NFR Products · c2025
-
-

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...
+ +
+ 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...
+
+
+
+ let controlState="idle"; + let autoModeEnabled=false; + let selectedGamepadIndex=-1; + let gamepads={}; + let gamepadDetected=false; + + const headerEl=document.getElementById('appHeader'); +const headerStatusValue=document.getElementById('headerStatusValue'); +const headerStatusDetail=document.getElementById('headerStatusDetail'); + +const loggingElements={ + pill:document.getElementById('loggingStatePill'), + detail:document.getElementById('loggingDetail'), + ssid:document.getElementById('loggingSsid'), + ip:document.getElementById('loggingIp'), + clients:document.getElementById('loggingClients'), + rate:document.getElementById('loggingRate'), + toggleBtn:document.getElementById('loggingToggleButton'), + refreshBtn:document.getElementById('loggingRefreshButton'), + clearBtn:document.getElementById('loggingClearButton'), + autoRefresh:document.getElementById('loggingAutoRefresh'), + autoScroll:document.getElementById('loggingAutoScroll'), + lastUpdated:document.getElementById('loggingLastUpdated'), + stream:document.getElementById('wifiLogStream'), + downloadBtn:document.getElementById('loggingDownloadButton') +}; + +const LOGGING_ENDPOINTS={ + status:"/logging/status", + toggle:"/logging/toggle", + clear:"/logging/clear", + stream:"/logging/stream?tail=200", + download:"/logging/download" +}; + +let loggingState={ + connected:false, + streaming:false, + ssid:"—", + ip:"—", + clients:0, + rate:0, + lastSync:null +}; +let loggingPollingTimer=null; +let loggingBusy=false; + +function setLoggingLastUpdated(text){ + if(loggingElements.lastUpdated){ + loggingElements.lastUpdated.textContent=`Last sync: ${text}`; + } +} + +function formatRate(value){ + if(typeof value!=="number" || !isFinite(value) || value<0){ + return "0 KB/s"; + } + const kb=value/1024; + if(kb>=1024){ + return `${(kb/1024).toFixed(1)} MB/s`; + } + return `${Math.max(0,kb).toFixed(1)} KB/s`; +} + +function applyLoggingState(data){ + loggingState.connected=!!data.connected; + loggingState.streaming=!!data.streaming; + loggingState.ssid=data.ssid || "—"; + loggingState.ip=data.ip || "—"; + loggingState.clients=Number.isFinite(data.clients)?data.clients:0; + loggingState.rate=Number.isFinite(data.rate)?data.rate:0; + loggingState.lastSync=new Date(); + + if(loggingElements.ssid) loggingElements.ssid.textContent=loggingState.ssid; + if(loggingElements.ip) loggingElements.ip.textContent=loggingState.ip; + if(loggingElements.clients) loggingElements.clients.textContent=String(loggingState.clients); + if(loggingElements.rate) loggingElements.rate.textContent=formatRate(loggingState.rate); + + if(loggingElements.pill){ + const mode=loggingState.streaming ? "streaming" : (loggingState.connected ? "connected" : "disconnected"); + loggingElements.pill.dataset.state=mode; + loggingElements.pill.textContent=mode==="streaming" ? "Streaming" : mode==="connected" ? "Connected" : "Disconnected"; + } + if(loggingElements.detail){ + loggingElements.detail.textContent=data.detail || (loggingState.connected ? "Ready to stream logs." : "Waiting for Wi-Fi module..."); + } + + if(loggingElements.toggleBtn){ + loggingElements.toggleBtn.disabled=false; + loggingElements.toggleBtn.classList.toggle('primary',!loggingState.streaming); + loggingElements.toggleBtn.classList.toggle('danger',loggingState.streaming); + loggingElements.toggleBtn.textContent=loggingState.streaming ? "Stop Logging" : "Start Logging"; + } + + setLoggingLastUpdated(loggingState.lastSync.toLocaleTimeString()); +} + +function setLoggingOffline(message){ + loggingState.connected=false; + loggingState.streaming=false; + loggingState.ssid="—"; + loggingState.ip="—"; + loggingState.clients=0; + loggingState.rate=0; + if(loggingElements.ssid) loggingElements.ssid.textContent="—"; + if(loggingElements.ip) loggingElements.ip.textContent="—"; + if(loggingElements.clients) loggingElements.clients.textContent="0"; + if(loggingElements.rate) loggingElements.rate.textContent="0 KB/s"; + if(loggingElements.pill){ + loggingElements.pill.dataset.state="disconnected"; + loggingElements.pill.textContent="Disconnected"; + } + if(loggingElements.detail){ + loggingElements.detail.textContent=message || "Wi-Fi logging unavailable."; + } + if(loggingElements.toggleBtn){ + loggingElements.toggleBtn.disabled=false; + loggingElements.toggleBtn.classList.add('primary'); + loggingElements.toggleBtn.classList.remove('danger'); + loggingElements.toggleBtn.textContent="Start Logging"; + } + setLoggingLastUpdated("offline"); +} + +function setLoggingError(message){ + if(loggingElements.pill){ + loggingElements.pill.dataset.state="error"; + loggingElements.pill.textContent="Error"; + } + if(loggingElements.detail){ + loggingElements.detail.textContent=message || "Command failed."; + } +} + +async function refreshLoggingStatus(silent=false){ + try{ + const res=await fetch(LOGGING_ENDPOINTS.status,{cache:"no-store"}); + if(!res.ok) throw new Error(`status ${res.status}`); + const payload=await res.json(); + applyLoggingState(payload); + }catch(err){ + if(!silent) console.error("logging status error",err); + setLoggingOffline("No response from robot."); + } +} + +async function refreshLogStream(silent=false){ + if(!loggingElements.stream) return; + try{ + const res=await fetch(LOGGING_ENDPOINTS.stream,{cache:"no-store"}); + if(!res.ok) throw new Error(`stream ${res.status}`); + const text=await res.text(); + updateLogStream(text || "No log data yet."); + }catch(err){ + if(!silent) console.error("log stream error",err); + } +} + +function updateLogStream(content){ + if(!loggingElements.stream) return; + loggingElements.stream.textContent=content; + if(loggingElements.autoScroll && loggingElements.autoScroll.checked){ + loggingElements.stream.scrollTop=loggingElements.stream.scrollHeight; + } +} + +function setLoggingAutoRefresh(enabled){ + if(loggingPollingTimer){ + clearInterval(loggingPollingTimer); + loggingPollingTimer=null; + } + if(enabled){ + loggingPollingTimer=setInterval(()=>{ + refreshLoggingStatus(true); + refreshLogStream(true); + },4000); + } +} + +async function handleLoggingToggle(){ + if(loggingBusy) return; + if(!loggingElements.toggleBtn) return; + loggingBusy=true; + loggingElements.toggleBtn.disabled=true; + const targetAction=loggingState.streaming ? "stop" : "start"; + loggingElements.toggleBtn.textContent=targetAction==="stop" ? "Stopping..." : "Starting..."; + try{ + const res=await fetch(LOGGING_ENDPOINTS.toggle,{ + method:"POST", + headers:{"Content-Type":"application/json"}, + body:JSON.stringify({action:targetAction}) + }); + if(!res.ok) throw new Error(`toggle ${res.status}`); + }catch(err){ + console.error("logging toggle error",err); + setLoggingError("Unable to toggle logging."); + }finally{ + loggingBusy=false; + await refreshLoggingStatus(true); + await refreshLogStream(true); + } +} + +async function handleLoggingClear(){ + if(loggingBusy) return; + try{ + const res=await fetch(LOGGING_ENDPOINTS.clear,{method:"POST"}); + if(!res.ok) throw new Error(`clear ${res.status}`); + updateLogStream("Log buffer cleared."); + await refreshLogStream(true); + }catch(err){ + console.error("logging clear error",err); + setLoggingError("Unable to clear buffer."); + } +} + +function handleLoggingDownload(){ + window.open(LOGGING_ENDPOINTS.download,"_blank","noopener"); +} + +function handleLoggingRefresh(){ + refreshLoggingStatus(); + refreshLogStream(); +} + +function setPhaseDisplay(mode){ + const map={ + init:{title:"Init", detail:"Systems primed"}, + auto:{title:"Autonomous", detail:"Running script"}, + teleop:{title:"Teleop", detail:"Drivers in control"}, + stopped:{title:"Stopped", detail:"Motors safe"}, + standby:{title:"Standby", detail:"Awaiting command"} + }; + const next = map[mode] || map.standby; + if(headerStatusValue){ + headerStatusValue.textContent = next.title; + } + if(headerStatusDetail){ + if(mode === 'auto'){ + headerStatusDetail.textContent = `Auto running – ${autoRemaining.toFixed(1)} s`; + }else{ + headerStatusDetail.textContent = next.detail; + } + } + document.body.dataset.state = mode; +} + +let autoTimer=null; +let autoRemaining=0; +const DEFAULT_BUTTON_COUNT=12; +const BUTTON_LABELS=["A","B","X","Y","LB","RB","LT","RT","Back","Start","L3","R3","P13","P14","P15","P16","P17","P18","P19","P20"]; + +function ensureJoyButtons(count){ + const container=document.getElementById('joyButtons'); + if(container.childElementCount === count) return; + container.innerHTML=""; + for(let i=0;i0 ? gp.axes[0] : 0; + const y=gp.axes && gp.axes.length>1 ? gp.axes[1] : 0; + dot.style.left=`${50 + x*45}%`; + dot.style.top=`${50 + y*45}%`; + ensureJoyButtons(gp.buttons.length); + gp.buttons.forEach((btn,i)=>{ + const node=container.children[i]; + if(node) node.classList.toggle('active', !!btn.pressed); + }); + }else{ + ensureJoyButtons(DEFAULT_BUTTON_COUNT); + dot.style.left='50%'; + dot.style.top='50%'; + Array.from(container.children).forEach(node=>node.classList.remove('active')); + } +} + +function updateAutoDisplay(){ + const display=document.getElementById('autoCountdown'); + const fill=document.getElementById('autoProgress'); + const duration=parseFloat(document.getElementById('autoPeriod').value)||0; + display.textContent=`${autoRemaining.toFixed(1)} s`; + const pct = duration>0 ? Math.max(0,Math.min(100,(autoRemaining/duration)*100)) : 0; + fill.style.width=`${pct}%`; + if(autoModeEnabled){ + setPhaseDisplay('auto'); + } +} + +function startAutoTimer(duration){ + autoModeEnabled = true; + autoRemaining = duration; + updateAutoDisplay(); + clearInterval(autoTimer); + autoTimer = setInterval(()=>{ + autoRemaining = Math.max(0, autoRemaining - 0.1); + updateAutoDisplay(); + if(autoRemaining <= 0){ + clearInterval(autoTimer); + autoTimer=null; + autoModeEnabled = false; + setPhaseDisplay('teleop'); + } + }, 100); +} + +function stopAutoTimer(){ + clearInterval(autoTimer); + autoTimer=null; + autoRemaining=0; + autoModeEnabled=false; + updateAutoDisplay(); +} + + async function handleRobotButton(){ + let cmd=""; + const enableAuto=document.getElementById('enableAutonomous').checked; + const autoLen=Math.max(0, parseFloat(document.getElementById('autoPeriod').value) || 0); + + switch(controlState){ + case "idle": cmd="init"; break; + case "armed": cmd="start"; break; + default: cmd="stop"; break; + } + + const url=`/robotControl?cmd=${cmd}&auto=${enableAuto?1:0}&autoLen=${autoLen}`; + try{ + const r=await fetch(url); + if(!r.ok) throw new Error("Robot command failed"); + }catch(err){ + console.error(err); + return; + } + + const btn=document.getElementById('robotButton'); + if(controlState==="idle"){ + controlState="armed"; + btn.textContent="Start"; + btn.style.background="var(--start)"; + btn.style.color="var(--ice)"; + stopAutoTimer(); + autoRemaining = autoLen; + updateAutoDisplay(); + setPhaseDisplay('init'); + }else if(controlState==="armed"){ + controlState="running"; + btn.textContent="Stop"; + btn.style.background="var(--stop)"; + btn.style.color="var(--ice)"; + if(enableAuto && autoLen>0){ + startAutoTimer(autoLen); + setPhaseDisplay('auto'); + }else{ + stopAutoTimer(); + setPhaseDisplay('teleop'); + } + }else{ + controlState="idle"; + btn.textContent="Init"; + btn.style.background="var(--navy)"; + btn.style.color="var(--ice)"; + stopAutoTimer(); + setPhaseDisplay('stopped'); + } + } + document.getElementById('robotButton').addEventListener('click',handleRobotButton); + + function updateGamepads(){ + const gpList=navigator.getGamepads?navigator.getGamepads():[]; + gamepads={}; + for(let i=0;i1){ selectEl.remove(1); } + Object.keys(gamepads).forEach(idx=>{ + const gp=gamepads[idx]; + const option=document.createElement('option'); + option.value=idx; + option.text=`${gp.id} (idx ${gp.index})`; + selectEl.add(option); + }); + if(Object.keys(gamepads).length>0 && selectedGamepadIndex<0){ + const firstIdx=Object.keys(gamepads)[0]; + selectEl.value=firstIdx; + selectedGamepadIndex=parseInt(firstIdx,10); + } + if(Object.keys(gamepads).length===0){ + selectedGamepadIndex=-1; + selectEl.value="-1"; + } + } + function changeSelectedGamepad(){ + const val=document.getElementById('joystickSelect').value; + selectedGamepadIndex=parseInt(val,10); + if(isNaN(selectedGamepadIndex)) selectedGamepadIndex=-1; + } + async function sendGamepadData(gp){ + const data={axes:gp.axes,buttons:gp.buttons.map(b=>b.pressed)}; + try{ + await fetch("/updateController",{ + method:"POST", + headers:{"Content-Type":"application/json"}, + body:JSON.stringify(data) + }); + }catch(err){ + console.error(err); + } + } + function displayJoystickData(gp){ + document.getElementById('joystickStatus').textContent=`${gp.id}\nAxes:${gp.axes.length} Buttons:${gp.buttons.length}`; + document.getElementById('axisData').textContent=gp.axes.map((v,i)=>`Axis ${i}: ${v.toFixed(2)}`).join("\n"); + document.getElementById('buttonData').textContent=gp.buttons.map((b,i)=>`${b.pressed?"●":"○"} ${i}`).join(" "); + document.getElementById('joystickStatusTxt').textContent="Connected"; + updateJoyVisuals(gp); + } + function gamepadLoop(){ + updateGamepads(); + rebuildGamepadSelect(); + const txt=document.getElementById('joystickStatusTxt'); + const hint=document.getElementById('gamepadHint'); + const gp=gamepads[selectedGamepadIndex]; + if(gp){ + txt.textContent="Connected"; + hint.style.display="none"; + gamepadDetected=true; + displayJoystickData(gp); + sendGamepadData(gp); + }else{ + txt.textContent="Not Connected"; + if(!gamepadDetected) hint.style.display="block"; + document.getElementById('joystickStatus').textContent="No gamepad selected."; + document.getElementById('axisData').textContent="No axis data..."; + document.getElementById('buttonData').textContent="No button data..."; + updateJoyVisuals(null); + } + requestAnimationFrame(gamepadLoop); + } + +if(loggingElements.toggleBtn) loggingElements.toggleBtn.addEventListener('click',handleLoggingToggle); +if(loggingElements.refreshBtn) loggingElements.refreshBtn.addEventListener('click',handleLoggingRefresh); +if(loggingElements.clearBtn) loggingElements.clearBtn.addEventListener('click',handleLoggingClear); +if(loggingElements.downloadBtn) loggingElements.downloadBtn.addEventListener('click',handleLoggingDownload); +if(loggingElements.autoRefresh) loggingElements.autoRefresh.addEventListener('change',e=>{ + setLoggingAutoRefresh(e.target.checked); + if(e.target.checked){ + handleLoggingRefresh(); + } +}); +if(loggingElements.autoScroll) loggingElements.autoScroll.addEventListener('change',()=>{ + if(loggingElements.autoScroll.checked && loggingElements.stream){ + loggingElements.stream.scrollTop=loggingElements.stream.scrollHeight; + } +}); + + window.addEventListener('gamepadconnected',()=>{ + updateGamepads(); + rebuildGamepadSelect(); + }); + window.addEventListener('gamepaddisconnected',e=>{ + delete gamepads[e.gamepad.index]; + }); + window.addEventListener('load',()=>{ + ensureJoyButtons(DEFAULT_BUTTON_COUNT); + updateJoyVisuals(null); + autoRemaining=parseFloat(document.getElementById('autoPeriod').value)||0; + updateAutoDisplay(); + setPhaseDisplay('standby'); + applyHeaderMode(); + handleLoggingRefresh(); + if(loggingElements.autoRefresh){ + setLoggingAutoRefresh(loggingElements.autoRefresh.checked); + } + requestAnimationFrame(gamepadLoop); + }); + + document.getElementById('autoPeriod').addEventListener('input',e=>{ + const duration=parseFloat(e.target.value)||0; + if(autoTimer){ + autoRemaining=Math.min(autoRemaining,duration); + } else { + autoRemaining=duration; + } + updateAutoDisplay(); + }); + + document.getElementById('enableAutonomous').addEventListener('change',e=>{ + if(!e.target.checked){ + stopAutoTimer(); + } + }); + -)====="; \ No newline at end of file + +)====="; diff --git a/ui-testing/README.md b/ui-testing/README.md index d226192..e5dcfdf 100644 --- a/ui-testing/README.md +++ b/ui-testing/README.md @@ -58,6 +58,19 @@ python3 ui-testing/server.py --html ui-testing/variants/base.html kullanır. Parametreyi boş bırakırsanız kütüphanedeki gömülü `index_html.h` okunmaya devam eder (donanım gerçekliğini test etmek için yararlı). +## Wi-Fi Logging UI + +- `minimal_stack.html` arayüzü içinde yeni **Wi-Fi Logging** kartı bulunur. +- Kart, `/logging/status` uç noktasından durumu okur, `Start/Stop` düğmesiyle + `/logging/toggle` komutunu gönderir, `Clear` ise `/logging/clear` çağırır. +- Log akışı `System Logs` kartında `Wi-Fi Log Stream` alanına `/logging/stream` + cevabını yazar; `Download` düğmesi `/logging/download` bağlantısını yeni + sekmede açar. +- Varsayılan olarak her 4 saniyede bir durum ve log bilgileri tazelenir. +- Otomatik yenileme ve kaydırma kapatılabilir; bu sayede ESP tarafındaki + Wi-Fi logging altyapısı hazır olduğunda arayüz ek gelişmeye gerek kalmadan + çalışır. + ## Tüm Varyantları Aynı Anda Görmek - 10 örnek tasarımı (port 9030–9039) aynı anda açmak için: diff --git a/ui-testing/variants/minimal_stack.html b/ui-testing/variants/minimal_stack.html index 9d31465..473368d 100644 --- a/ui-testing/variants/minimal_stack.html +++ b/ui-testing/variants/minimal_stack.html @@ -9,6 +9,7 @@ --ice:#e5e4e2; --start:#28a745; --stop:#d93025; + --sky:#0aa6d9; font-family:"Inter","Segoe UI",sans-serif; } *{margin:0;padding:0;box-sizing:border-box;} @@ -405,6 +406,176 @@ color:rgba(0,32,77,0.6); letter-spacing:0.06em; } + .logging-status{ + display:flex; + flex-direction:column; + gap:6px; + margin-bottom:16px; + } + .status-pill{ + display:inline-flex; + align-items:center; + gap:8px; + padding:6px 12px; + border-radius:999px; + font-size:0.75rem; + letter-spacing:0.12em; + text-transform:uppercase; + background:rgba(0,32,77,0.15); + color:var(--navy); + font-weight:600; + transition:background 160ms ease, color 160ms ease; + } + .status-pill[data-state="connected"]{ + background:var(--start); + color:var(--ice); + } + .status-pill[data-state="streaming"]{ + background:linear-gradient(135deg,var(--start),rgba(0,32,77,0.7)); + color:var(--ice); + } + .status-pill[data-state="error"]{ + background:var(--stop); + color:var(--ice); + } + .logging-detail{ + font-size:0.9rem; + color:rgba(0,32,77,0.75); + letter-spacing:0.04em; + } + .logging-metrics{ + display:grid; + grid-template-columns:repeat(auto-fit,minmax(140px,1fr)); + gap:12px; + margin-bottom:16px; + } + .logging-metric{ + background:rgba(229,228,226,0.9); + border-radius:14px; + padding:12px 14px; + border:1px solid rgba(0,32,77,0.1); + display:flex; + flex-direction:column; + gap:4px; + min-height:70px; + } + .logging-metric-label{ + font-size:0.72rem; + text-transform:uppercase; + letter-spacing:0.14em; + color:rgba(0,32,77,0.55); + } + .logging-metric-value{ + font-size:1.1rem; + letter-spacing:0.04em; + color:rgba(0,32,77,0.85); + word-break:break-word; + } + .logging-actions{ + display:flex; + flex-wrap:wrap; + gap:10px; + margin-bottom:12px; + } + .logging-actions button{ + flex:1 1 120px; + padding:12px; + border:none; + border-radius:14px; + font-size:0.9rem; + letter-spacing:0.08em; + text-transform:uppercase; + cursor:pointer; + transition:transform 140ms ease, box-shadow 140ms ease, background 140ms ease; + background:rgba(0,32,77,0.12); + color:var(--navy); + box-shadow:0 6px 12px rgba(0,32,77,0.14); + } + .logging-actions button:hover{ + transform:translateY(-1px); + } + .logging-actions button:active{ + transform:translateY(1px); + box-shadow:0 4px 8px rgba(0,32,77,0.2); + } + .logging-actions button.primary{ + background:var(--navy); + color:var(--ice); + } + .logging-actions button.danger{ + background:var(--stop); + color:var(--ice); + } + .logging-options{ + display:flex; + flex-wrap:wrap; + gap:12px; + align-items:center; + font-size:0.88rem; + letter-spacing:0.04em; + color:rgba(0,32,77,0.75); + margin-bottom:16px; + } + .logging-options label{ + display:flex; + align-items:center; + gap:6px; + } + .logging-options input[type="checkbox"]{ + accent-color:var(--navy); + width:16px; + height:16px; + } + .logging-stream{ + margin-top:20px; + display:flex; + flex-direction:column; + gap:10px; + } + .logging-stream-header{ + display:flex; + justify-content:space-between; + align-items:center; + font-size:0.86rem; + letter-spacing:0.04em; + color:rgba(0,32,77,0.7); + } + .logging-stream-header strong{ + font-size:0.9rem; + color:rgba(0,32,77,0.85); + } + .logging-stream-header button{ + background:rgba(0,32,77,0.12); + color:var(--navy); + border:none; + padding:6px 12px; + border-radius:10px; + letter-spacing:0.08em; + text-transform:uppercase; + font-size:0.72rem; + cursor:pointer; + box-shadow:none; + transition:background 120ms ease, transform 120ms ease; + } + .logging-stream-header button:hover{ + background:rgba(0,32,77,0.22); + transform:translateY(-1px); + } + .logging-stream-header button:active{ + transform:translateY(1px); + } + #wifiLogStream{ + height:160px; + border-radius:14px; + padding:16px; + border:1px solid rgba(0,32,77,0.12); + background:var(--ice); + font-family:"SFMono-Regular","Roboto Mono",monospace; + color:var(--navy); + line-height:1.45; + white-space:pre-wrap; + overflow:auto; + } @media(max-width:992px){ .app-header{ padding:16px 28px; @@ -692,14 +863,62 @@

Joystick Check

+
+

Wi-Fi Logging

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

Telemetry Log

+

System Logs

No gamepad selected.
No axis data...
No button data...
+
+
+ Wi-Fi Log Stream + +
+
Waiting for log data...
+
@@ -711,8 +930,223 @@

Telemetry Log

let gamepadDetected=false; const headerEl=document.getElementById('appHeader'); - const headerStatusValue=document.getElementById('headerStatusValue'); - const headerStatusDetail=document.getElementById('headerStatusDetail'); +const headerStatusValue=document.getElementById('headerStatusValue'); +const headerStatusDetail=document.getElementById('headerStatusDetail'); + +const loggingElements={ + pill:document.getElementById('loggingStatePill'), + detail:document.getElementById('loggingDetail'), + ssid:document.getElementById('loggingSsid'), + ip:document.getElementById('loggingIp'), + clients:document.getElementById('loggingClients'), + rate:document.getElementById('loggingRate'), + toggleBtn:document.getElementById('loggingToggleButton'), + refreshBtn:document.getElementById('loggingRefreshButton'), + clearBtn:document.getElementById('loggingClearButton'), + autoRefresh:document.getElementById('loggingAutoRefresh'), + autoScroll:document.getElementById('loggingAutoScroll'), + lastUpdated:document.getElementById('loggingLastUpdated'), + stream:document.getElementById('wifiLogStream'), + downloadBtn:document.getElementById('loggingDownloadButton') +}; + +const LOGGING_ENDPOINTS={ + status:"/logging/status", + toggle:"/logging/toggle", + clear:"/logging/clear", + stream:"/logging/stream?tail=200", + download:"/logging/download" +}; + +let loggingState={ + connected:false, + streaming:false, + ssid:"—", + ip:"—", + clients:0, + rate:0, + lastSync:null +}; +let loggingPollingTimer=null; +let loggingBusy=false; + +function setLoggingLastUpdated(text){ + if(loggingElements.lastUpdated){ + loggingElements.lastUpdated.textContent=`Last sync: ${text}`; + } +} + +function formatRate(value){ + if(typeof value!=="number" || !isFinite(value) || value<0){ + return "0 KB/s"; + } + const kb=value/1024; + if(kb>=1024){ + return `${(kb/1024).toFixed(1)} MB/s`; + } + return `${Math.max(0,kb).toFixed(1)} KB/s`; +} + +function applyLoggingState(data){ + loggingState.connected=!!data.connected; + loggingState.streaming=!!data.streaming; + loggingState.ssid=data.ssid || "—"; + loggingState.ip=data.ip || "—"; + loggingState.clients=Number.isFinite(data.clients)?data.clients:0; + loggingState.rate=Number.isFinite(data.rate)?data.rate:0; + loggingState.lastSync=new Date(); + + if(loggingElements.ssid) loggingElements.ssid.textContent=loggingState.ssid; + if(loggingElements.ip) loggingElements.ip.textContent=loggingState.ip; + if(loggingElements.clients) loggingElements.clients.textContent=String(loggingState.clients); + if(loggingElements.rate) loggingElements.rate.textContent=formatRate(loggingState.rate); + + if(loggingElements.pill){ + const mode=loggingState.streaming ? "streaming" : (loggingState.connected ? "connected" : "disconnected"); + loggingElements.pill.dataset.state=mode; + loggingElements.pill.textContent=mode==="streaming" ? "Streaming" : mode==="connected" ? "Connected" : "Disconnected"; + } + if(loggingElements.detail){ + loggingElements.detail.textContent=data.detail || (loggingState.connected ? "Ready to stream logs." : "Waiting for Wi-Fi module..."); + } + + if(loggingElements.toggleBtn){ + loggingElements.toggleBtn.disabled=false; + loggingElements.toggleBtn.classList.toggle('primary',!loggingState.streaming); + loggingElements.toggleBtn.classList.toggle('danger',loggingState.streaming); + loggingElements.toggleBtn.textContent=loggingState.streaming ? "Stop Logging" : "Start Logging"; + } + + setLoggingLastUpdated(loggingState.lastSync.toLocaleTimeString()); +} + +function setLoggingOffline(message){ + loggingState.connected=false; + loggingState.streaming=false; + loggingState.ssid="—"; + loggingState.ip="—"; + loggingState.clients=0; + loggingState.rate=0; + if(loggingElements.ssid) loggingElements.ssid.textContent="—"; + if(loggingElements.ip) loggingElements.ip.textContent="—"; + if(loggingElements.clients) loggingElements.clients.textContent="0"; + if(loggingElements.rate) loggingElements.rate.textContent="0 KB/s"; + if(loggingElements.pill){ + loggingElements.pill.dataset.state="disconnected"; + loggingElements.pill.textContent="Disconnected"; + } + if(loggingElements.detail){ + loggingElements.detail.textContent=message || "Wi-Fi logging unavailable."; + } + if(loggingElements.toggleBtn){ + loggingElements.toggleBtn.disabled=false; + loggingElements.toggleBtn.classList.add('primary'); + loggingElements.toggleBtn.classList.remove('danger'); + loggingElements.toggleBtn.textContent="Start Logging"; + } + setLoggingLastUpdated("offline"); +} + +function setLoggingError(message){ + if(loggingElements.pill){ + loggingElements.pill.dataset.state="error"; + loggingElements.pill.textContent="Error"; + } + if(loggingElements.detail){ + loggingElements.detail.textContent=message || "Command failed."; + } +} + +async function refreshLoggingStatus(silent=false){ + try{ + const res=await fetch(LOGGING_ENDPOINTS.status,{cache:"no-store"}); + if(!res.ok) throw new Error(`status ${res.status}`); + const payload=await res.json(); + applyLoggingState(payload); + }catch(err){ + if(!silent) console.error("logging status error",err); + setLoggingOffline("No response from robot."); + } +} + +async function refreshLogStream(silent=false){ + if(!loggingElements.stream) return; + try{ + const res=await fetch(LOGGING_ENDPOINTS.stream,{cache:"no-store"}); + if(!res.ok) throw new Error(`stream ${res.status}`); + const text=await res.text(); + updateLogStream(text || "No log data yet."); + }catch(err){ + if(!silent) console.error("log stream error",err); + } +} + +function updateLogStream(content){ + if(!loggingElements.stream) return; + loggingElements.stream.textContent=content; + if(loggingElements.autoScroll && loggingElements.autoScroll.checked){ + loggingElements.stream.scrollTop=loggingElements.stream.scrollHeight; + } +} + +function setLoggingAutoRefresh(enabled){ + if(loggingPollingTimer){ + clearInterval(loggingPollingTimer); + loggingPollingTimer=null; + } + if(enabled){ + loggingPollingTimer=setInterval(()=>{ + refreshLoggingStatus(true); + refreshLogStream(true); + },4000); + } +} + +async function handleLoggingToggle(){ + if(loggingBusy) return; + if(!loggingElements.toggleBtn) return; + loggingBusy=true; + loggingElements.toggleBtn.disabled=true; + const targetAction=loggingState.streaming ? "stop" : "start"; + loggingElements.toggleBtn.textContent=targetAction==="stop" ? "Stopping..." : "Starting..."; + try{ + const res=await fetch(LOGGING_ENDPOINTS.toggle,{ + method:"POST", + headers:{"Content-Type":"application/json"}, + body:JSON.stringify({action:targetAction}) + }); + if(!res.ok) throw new Error(`toggle ${res.status}`); + }catch(err){ + console.error("logging toggle error",err); + setLoggingError("Unable to toggle logging."); + }finally{ + loggingBusy=false; + await refreshLoggingStatus(true); + await refreshLogStream(true); + } +} + +async function handleLoggingClear(){ + if(loggingBusy) return; + try{ + const res=await fetch(LOGGING_ENDPOINTS.clear,{method:"POST"}); + if(!res.ok) throw new Error(`clear ${res.status}`); + updateLogStream("Log buffer cleared."); + await refreshLogStream(true); + }catch(err){ + console.error("logging clear error",err); + setLoggingError("Unable to clear buffer."); + } +} + +function handleLoggingDownload(){ + window.open(LOGGING_ENDPOINTS.download,"_blank","noopener"); +} + +function handleLoggingRefresh(){ + refreshLoggingStatus(); + refreshLogStream(); +} function setPhaseDisplay(mode){ const map={ @@ -939,10 +1373,26 @@

Telemetry Log

} requestAnimationFrame(gamepadLoop); } - function varGet(name){ - return getComputedStyle(document.documentElement).getPropertyValue(name).trim()||varDefaults[name]; - } - const varDefaults={"--navy":"#00204d","--start":"#28a745","--stop":"#d93025","--ice":"#e5e4e2"}; +function varGet(name){ + return getComputedStyle(document.documentElement).getPropertyValue(name).trim()||varDefaults[name]; +} +const varDefaults={"--navy":"#00204d","--start":"#28a745","--stop":"#d93025","--ice":"#e5e4e2"}; + +if(loggingElements.toggleBtn) loggingElements.toggleBtn.addEventListener('click',handleLoggingToggle); +if(loggingElements.refreshBtn) loggingElements.refreshBtn.addEventListener('click',handleLoggingRefresh); +if(loggingElements.clearBtn) loggingElements.clearBtn.addEventListener('click',handleLoggingClear); +if(loggingElements.downloadBtn) loggingElements.downloadBtn.addEventListener('click',handleLoggingDownload); +if(loggingElements.autoRefresh) loggingElements.autoRefresh.addEventListener('change',e=>{ + setLoggingAutoRefresh(e.target.checked); + if(e.target.checked){ + handleLoggingRefresh(); + } +}); +if(loggingElements.autoScroll) loggingElements.autoScroll.addEventListener('change',()=>{ + if(loggingElements.autoScroll.checked && loggingElements.stream){ + loggingElements.stream.scrollTop=loggingElements.stream.scrollHeight; + } +}); window.addEventListener('gamepadconnected',()=>{ updateGamepads(); @@ -958,6 +1408,10 @@

Telemetry Log

updateAutoDisplay(); setPhaseDisplay('standby'); applyHeaderMode(); + handleLoggingRefresh(); + if(loggingElements.autoRefresh){ + setLoggingAutoRefresh(loggingElements.autoRefresh.checked); + } requestAnimationFrame(gamepadLoop); }); From 09f3552f99c37b87f0951e1074584351e6dbffba Mon Sep 17 00:00:00 2001 From: tunapro Date: Sat, 18 Oct 2025 19:12:33 +0300 Subject: [PATCH 21/26] Hook logging transport into minimal UI with safe ring buffer --- .../esp32s3/web/driver_station_esp32.hpp | 74 +++++- src/probot/logging/logger.cpp | 243 +++++++++++++++++- src/probot/logging/logger.hpp | 25 ++ ui-testing/variants/minimal_stack.html | 32 ++- 4 files changed, 363 insertions(+), 11 deletions(-) diff --git a/src/platform/esp32s3/web/driver_station_esp32.hpp b/src/platform/esp32s3/web/driver_station_esp32.hpp index 2e0775b..11886d1 100644 --- a/src/platform/esp32s3/web/driver_station_esp32.hpp +++ b/src/platform/esp32s3/web/driver_station_esp32.hpp @@ -5,6 +5,7 @@ #include #include #include +#include #include "index_html.h" #if defined(PROBOT_WITH_DS) && !defined(PROBOT_WIFI_AP_PASSWORD) @@ -31,6 +32,7 @@ namespace probot::platform::esp32 { return; } String ssid = generateSSID(); + ap_ssid_ = ssid; WiFi.mode(WIFI_AP); WiFi.softAP(ssid.c_str(), pw); @@ -47,6 +49,11 @@ 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.begin(); } @@ -129,12 +136,77 @@ 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()); + } + robot::StateService& _rs; io::GamepadService& _gs; WebServer _server; const char* _apPass; bool _owner_set=false; IPAddress _owner; + String ap_ssid_; }; } -#endif // ESP32 \ No newline at end of file +#endif // ESP32 diff --git a/src/probot/logging/logger.cpp b/src/probot/logging/logger.cpp index e21b682..5808f01 100644 --- a/src/probot/logging/logger.cpp +++ b/src/probot/logging/logger.cpp @@ -3,6 +3,13 @@ #include #include #include +#include +#if defined(ESP32) +#include +#include +#else +#include +#endif namespace probot::logging { @@ -15,6 +22,21 @@ namespace { constexpr size_t kMaxInstanceLen = 32; constexpr size_t kMaxFieldLen = 24; constexpr size_t kMaxTextLen = 64; + constexpr size_t kLogLineCapacity = 160; + +#if defined(ESP32) + static portMUX_TYPE g_log_mux = portMUX_INITIALIZER_UNLOCKED; + struct ScopedLock { + ScopedLock(){ portENTER_CRITICAL(&g_log_mux); } + ~ScopedLock(){ portEXIT_CRITICAL(&g_log_mux); } + }; +#else + static std::mutex g_log_mutex; + struct ScopedLock { + ScopedLock(){ g_log_mutex.lock(); } + ~ScopedLock(){ g_log_mutex.unlock(); } + }; +#endif struct SourceRecord { bool used; @@ -220,6 +242,21 @@ struct LoggingManager::Impl { TransportState serial; TransportState wifi; WifiSendFn wifi_writer; + bool wifi_streaming_enabled; + uint32_t wifi_bytes_sent; + uint32_t wifi_stream_start_ms; + uint32_t wifi_last_send_ms; + static constexpr size_t kHttpLogCapacity = 256; + char http_log[kHttpLogCapacity][kLogLineCapacity]; + uint8_t http_log_len[kHttpLogCapacity]; + size_t http_log_head; + size_t http_log_count; + uint32_t http_log_total; + uint32_t last_entry_ms; + + void appendHttpLog(const LogSample& sample); + void copyHttpLog(std::string& out, size_t max_lines) const; + void clearHttpLog(); }; LoggingManager& manager(){ @@ -241,6 +278,18 @@ LoggingManager::LoggingManager() impl_->wifi.endpoint_ip_be = 0; impl_->wifi.endpoint_port = 0; impl_->wifi_writer = nullptr; + impl_->wifi_streaming_enabled = true; + impl_->wifi_bytes_sent = 0; + impl_->wifi_stream_start_ms = 0; + impl_->wifi_last_send_ms = 0; + impl_->http_log_head = 0; + impl_->http_log_count = 0; + impl_->http_log_total = 0; + impl_->last_entry_ms = 0; + memset(impl_->http_log_len, 0, sizeof(impl_->http_log_len)); + for (size_t i=0;ihttp_log[i][0] = '\0'; + } } LoggingManager::~LoggingManager(){ @@ -254,26 +303,32 @@ LoggingManager& LoggingManager::instance(){ } void LoggingManager::enableSerial(bool enabled){ + ScopedLock guard; impl_->serial.enabled = enabled; } void LoggingManager::setSerialBandwidth(BandwidthMode mode){ + ScopedLock guard; impl_->serial.mode = mode; } void LoggingManager::enableWifi(bool enabled){ + ScopedLock guard; impl_->wifi.enabled = enabled; } void LoggingManager::setWifiBandwidth(BandwidthMode mode){ + ScopedLock guard; impl_->wifi.mode = mode; } void LoggingManager::setWifiSendCallbackInternal(WifiSendFn fn){ + ScopedLock guard; impl_->wifi_writer = fn; } void LoggingManager::setWifiEndpointInternal(uint32_t ipv4_be, uint16_t port){ + ScopedLock guard; impl_->wifi.endpoint_ip_be = ipv4_be; impl_->wifi.endpoint_port = port; } @@ -514,7 +569,12 @@ void LoggingManager::update(uint32_t now_ms, uint32_t dt_ms){ auto sendSerialFrame = [&](const LogSample& sample){ uint8_t frame[256]; size_t len = 0; - if (!encodeFrame(impl_->serial, sample, frame, sizeof(frame), len)){ + bool encoded = false; + { + ScopedLock guard; + encoded = encodeFrame(impl_->serial, sample, frame, sizeof(frame), len); + } + if (!encoded){ recordDrop(true, false); return; } @@ -523,22 +583,46 @@ void LoggingManager::update(uint32_t now_ms, uint32_t dt_ms){ recordDrop(true, false); return; } - impl_->serial.drop_counter = 0; + { + ScopedLock guard; + impl_->serial.drop_counter = 0; + } }; auto sendWifiFrame = [&](const LogSample& sample){ - if (!impl_->wifi_writer) return; uint8_t frame[256]; size_t len = 0; - if (!encodeFrame(impl_->wifi, sample, frame, sizeof(frame), len)){ + WifiSendFn writer = nullptr; + bool encoded = false; + bool streaming = false; + { + ScopedLock guard; + writer = impl_->wifi_writer; + streaming = impl_->wifi_streaming_enabled && impl_->wifi.enabled; + if (writer && streaming){ + encoded = encodeFrame(impl_->wifi, sample, frame, sizeof(frame), len); + } + } + if (!writer || !streaming){ + return; + } + if (!encoded){ recordDrop(false, true); return; } - if (!impl_->wifi_writer(frame, len)){ + if (!writer(frame, len)){ recordDrop(false, true); return; } - impl_->wifi.drop_counter = 0; + { + ScopedLock guard; + impl_->wifi.drop_counter = 0; + impl_->wifi_bytes_sent += static_cast(len); + impl_->wifi_last_send_ms = millis(); + if (impl_->wifi_stream_start_ms == 0){ + impl_->wifi_stream_start_ms = impl_->wifi_last_send_ms; + } + } }; while ((serial_budget > 0) || (wifi_budget > 0)){ @@ -574,6 +658,7 @@ void LoggingManager::emitStatic(const void* source){ } void LoggingManager::recordDrop(bool serial, bool wifi){ + ScopedLock guard; if (serial && impl_->serial.drop_counter < 0xFFFFu){ impl_->serial.drop_counter += 1; } @@ -582,6 +667,132 @@ void LoggingManager::recordDrop(bool serial, bool wifi){ } } +inline void LoggingManager::Impl::appendHttpLog(const LogSample& sample){ + ScopedLock guard; + char* dest = http_log[http_log_head]; + size_t cap = kLogLineCapacity; + size_t pos = 0; + auto appendChar = [&](char c){ if (pos + 1 < cap){ dest[pos++] = c; } }; + auto appendCStr = [&](const char* s){ if (!s) return; while (*s && pos + 1 < cap){ dest[pos++] = *s++; } }; + auto appendUInt = [&](uint32_t v){ char buf[16]; snprintf(buf, sizeof(buf), "%lu", static_cast(v)); appendCStr(buf); }; + auto appendInt = [&](int32_t v){ char buf[16]; snprintf(buf, sizeof(buf), "%ld", static_cast(v)); appendCStr(buf); }; + auto appendFloat = [&](float v){ char buf[20]; snprintf(buf, sizeof(buf), "%.4f", static_cast(v)); appendCStr(buf); }; + + appendChar('['); + appendUInt(sample.timestamp_ms); + appendCStr("] "); + switch (sample.priority){ + case Priority::kSystemCritical: appendCStr("SYS"); break; + case Priority::kUserMarked: appendCStr("USR"); break; + default: appendCStr("BG"); break; + } + appendChar(' '); + if (sample.reg && sample.reg->type_name){ + appendCStr(sample.reg->type_name); + if (sample.reg->instance_name){ + appendChar(':'); + appendCStr(sample.reg->instance_name); + } + } else { + appendCStr("component"); + } + appendChar(' '); + appendCStr(sample.field); + appendChar('='); + switch (sample.type){ + case ValueType::kInt: + appendInt(sample.int_value); + break; + case ValueType::kFloat: + appendFloat(sample.float_value); + break; + case ValueType::kBool: + appendCStr(sample.bool_value ? "true" : "false"); + break; + case ValueType::kString: + if (sample.has_text){ appendCStr(sample.text); } + break; + } + dest[pos] = '\0'; + http_log_len[http_log_head] = static_cast(pos); + http_log_head = (http_log_head + 1) % kHttpLogCapacity; + if (http_log_count < kHttpLogCapacity){ + http_log_count += 1; + } + http_log_total += 1; + last_entry_ms = sample.timestamp_ms; +} + +void LoggingManager::Impl::copyHttpLog(std::string& out, size_t max_lines) const{ + ScopedLock guard; + out.clear(); + if (http_log_count == 0){ + return; + } + size_t lines = http_log_count; + if (max_lines > 0 && lines > max_lines){ + lines = max_lines; + } + size_t start = (http_log_head + kHttpLogCapacity - http_log_count) % kHttpLogCapacity; + size_t idx = start; + for (size_t i = 0; i < lines; ++i){ + out += http_log[idx]; + if (i + 1 < lines) out += '\n'; + idx = (idx + 1) % kHttpLogCapacity; + } +} + +void LoggingManager::Impl::clearHttpLog(){ + ScopedLock guard; + for (size_t i = 0; i < kHttpLogCapacity; ++i){ + http_log[i][0] = '\0'; + http_log_len[i] = 0; + } + http_log_head = 0; + http_log_count = 0; + http_log_total = 0; + last_entry_ms = 0; +} + +void LoggingManager::setWifiStreamingEnabledInternal(bool enabled){ + ScopedLock guard; + impl_->wifi_streaming_enabled = enabled; + if (enabled){ + impl_->wifi_stream_start_ms = millis(); + impl_->wifi_bytes_sent = 0; + impl_->wifi_last_send_ms = 0; + } else { + impl_->wifi_stream_start_ms = 0; + impl_->wifi_last_send_ms = 0; + } +} + +bool LoggingManager::wifiStreamingEnabledInternal() const{ + ScopedLock guard; + return impl_->wifi_streaming_enabled; +} + +void LoggingManager::statusInternal(LoggingStatus& status) const{ + ScopedLock guard; + status.wifi_enabled = impl_->wifi.enabled; + status.wifi_streaming = impl_->wifi_streaming_enabled && impl_->wifi.enabled; + status.serial_drop = impl_->serial.drop_counter; + status.wifi_drop = impl_->wifi.drop_counter; + status.total_entries = impl_->http_log_total; + status.last_entry_ms = impl_->last_entry_ms; + status.wifi_bytes_sent = impl_->wifi_bytes_sent; + status.wifi_stream_start_ms = impl_->wifi_stream_start_ms; + status.wifi_last_send_ms = impl_->wifi_last_send_ms; +} + +void LoggingManager::copyLogLines(std::string& out, size_t max_lines) const{ + impl_->copyHttpLog(out, max_lines); +} + +void LoggingManager::clearLogLines(){ + impl_->clearHttpLog(); +} + ::control::IUpdatable* LoggingManager::wrap(::control::IUpdatable* object){ if (!object) return nullptr; WrapperRecord* existing = findWrapperRecord(object); @@ -844,4 +1055,24 @@ uint16_t wifiEndpointPort(){ return LoggingManager::instance().wifiEndpointPortInternal(); } +void setWifiStreamingEnabled(bool enabled){ + LoggingManager::instance().setWifiStreamingEnabledInternal(enabled); +} + +bool wifiStreamingEnabled(){ + return LoggingManager::instance().wifiStreamingEnabledInternal(); +} + +void loggingStatus(LoggingStatus& status){ + LoggingManager::instance().statusInternal(status); +} + +void loggingStream(std::string& out, size_t max_lines){ + LoggingManager::instance().copyLogLines(out, max_lines); +} + +void clearLoggingStream(){ + LoggingManager::instance().clearLogLines(); +} + } // namespace probot::logging diff --git a/src/probot/logging/logger.hpp b/src/probot/logging/logger.hpp index 5059731..27e1915 100644 --- a/src/probot/logging/logger.hpp +++ b/src/probot/logging/logger.hpp @@ -3,6 +3,8 @@ #include #include #include +#include +#include namespace probot::logging { @@ -66,6 +68,24 @@ namespace probot::logging { void emitStaticSnapshot(const void* source); uint32_t wifiEndpointIp(); uint16_t wifiEndpointPort(); + void setWifiStreamingEnabled(bool enabled); + bool wifiStreamingEnabled(); + + struct LoggingStatus { + bool wifi_enabled; + bool wifi_streaming; + uint16_t serial_drop; + uint16_t wifi_drop; + uint32_t total_entries; + uint32_t last_entry_ms; + uint32_t wifi_bytes_sent; + uint32_t wifi_stream_start_ms; + uint32_t wifi_last_send_ms; + }; + + void loggingStatus(LoggingStatus& status); + void loggingStream(std::string& out, size_t max_lines = 200); + void clearLoggingStream(); class TelemetryCollector { public: @@ -139,6 +159,11 @@ namespace probot::logging { void setWifiEndpointInternal(uint32_t ipv4_be, uint16_t port); uint32_t wifiEndpointIpInternal() const; uint16_t wifiEndpointPortInternal() const; + void setWifiStreamingEnabledInternal(bool enabled); + bool wifiStreamingEnabledInternal() const; + void statusInternal(struct LoggingStatus& status) const; + void copyLogLines(std::string& out, size_t max_lines) const; + void clearLogLines(); private: LoggingManager(); diff --git a/ui-testing/variants/minimal_stack.html b/ui-testing/variants/minimal_stack.html index 23d83da..d1976b2 100644 --- a/ui-testing/variants/minimal_stack.html +++ b/ui-testing/variants/minimal_stack.html @@ -1059,7 +1059,13 @@

System Logs

async function refreshLoggingStatus(silent=false){ try{ const res=await fetch(LOGGING_ENDPOINTS.status,{cache:"no-store"}); - if(!res.ok) throw new Error(`status ${res.status}`); + if(!res.ok){ + if(res.status===404 || res.status===501){ + setLoggingOffline('Logging service unavailable.'); + return; + } + throw new Error(`status ${res.status}`); + } const payload=await res.json(); applyLoggingState(payload); }catch(err){ @@ -1072,7 +1078,13 @@

System Logs

if(!loggingElements.stream) return; try{ const res=await fetch(LOGGING_ENDPOINTS.stream,{cache:"no-store"}); - if(!res.ok) throw new Error(`stream ${res.status}`); + if(!res.ok){ + if(res.status===404 || res.status===501){ + updateLogStream('Wi-Fi logging not supported on this firmware.'); + return; + } + throw new Error(`stream ${res.status}`); + } const text=await res.text(); updateLogStream(text || "No log data yet."); }catch(err){ @@ -1114,7 +1126,13 @@

System Logs

headers:{"Content-Type":"application/json"}, body:JSON.stringify({action:targetAction}) }); - if(!res.ok) throw new Error(`toggle ${res.status}`); + if(!res.ok){ + if(res.status===404 || res.status===501){ + setLoggingOffline('Logging control unavailable.'); + return; + } + throw new Error(`toggle ${res.status}`); + } }catch(err){ console.error("logging toggle error",err); setLoggingError("Unable to toggle logging."); @@ -1129,7 +1147,13 @@

System Logs

if(loggingBusy) return; try{ const res=await fetch(LOGGING_ENDPOINTS.clear,{method:"POST"}); - if(!res.ok) throw new Error(`clear ${res.status}`); + if(!res.ok){ + if(res.status===404 || res.status===501){ + setLoggingError('Logging buffer not supported.'); + return; + } + throw new Error(`clear ${res.status}`); + } updateLogStream("Log buffer cleared."); await refreshLogStream(true); }catch(err){ From ad62da819509704636c17c301ecd63b4e5f25b85 Mon Sep 17 00:00:00 2001 From: tunapro Date: Sat, 18 Oct 2025 20:06:22 +0300 Subject: [PATCH 22/26] refactor: remove motor handle abstraction --- .../BoardozaVNHMotorDemo.ino | 13 +++++----- examples/FullRobotDemo/FullRobotDemo.ino | 19 ++++++-------- examples/MotorTest/MotorTest.ino | 4 +-- .../AdvancedMecanumDrive.ino | 14 +++++----- .../AdvancedTankDrive/AdvancedTankDrive.ino | 19 +++++--------- src/probot.h | 1 - src/probot/devices/motors/motor_handle.hpp | 26 ------------------- tests/test_devices.cpp | 12 ++++----- 8 files changed, 33 insertions(+), 75 deletions(-) delete mode 100644 src/probot/devices/motors/motor_handle.hpp diff --git a/examples/BoardozaVNHMotorDemo/BoardozaVNHMotorDemo.ino b/examples/BoardozaVNHMotorDemo/BoardozaVNHMotorDemo.ino index 43c17d3..36a7188 100644 --- a/examples/BoardozaVNHMotorDemo/BoardozaVNHMotorDemo.ino +++ b/examples/BoardozaVNHMotorDemo/BoardozaVNHMotorDemo.ino @@ -43,7 +43,6 @@ static probot::motor::BoardozaVNHMotorDriver g_motor( PIN_ENA, PIN_ENB ); -static probot::motor::MotorHandle g_motorHandle(g_motor); static float g_lastReportedPower = 0.0f; static float applyDeadband(float value){ @@ -65,17 +64,17 @@ void robotInit(){ g_motor.begin(); g_motor.setBrakeMode(true); // boşta tam fren g_motor.setBrakeStrength(1.0f); // PWM %100 ile fren uygula - g_motorHandle.setPower(0.0f); + g_motor.setPower(0.0f); g_lastReportedPower = 0.0f; } void robotEnd(){ - g_motorHandle.setPower(0.0f); + g_motor.setPower(0.0f); Serial.println("[BoardozaVNH] Demo stopped"); } void teleopInit(){ - g_motorHandle.setPower(0.0f); + g_motor.setPower(0.0f); g_lastReportedPower = 0.0f; } @@ -89,14 +88,14 @@ void teleopLoop(){ power = applyDeadband(power); } - g_motorHandle.setPower(power); + g_motor.setPower(power); // İsteğe bağlı: bir düğmeye basıldığında yönü ters çevirmek /* if (snapshot.buttonCount > 0 && snapshot.buttons[0]){ - g_motorHandle.setInverted(true); + g_motor.setInverted(true); } else { - g_motorHandle.setInverted(false); + g_motor.setInverted(false); } */ diff --git a/examples/FullRobotDemo/FullRobotDemo.ino b/examples/FullRobotDemo/FullRobotDemo.ino index 233753a..5884c06 100644 --- a/examples/FullRobotDemo/FullRobotDemo.ino +++ b/examples/FullRobotDemo/FullRobotDemo.ino @@ -2,7 +2,6 @@ #include #include #include -#include // Bu örnek, daha tamamlanmış bir robot iskeleti gösterir: // - TankDrive şasi (teleop + otonom) @@ -28,10 +27,8 @@ static probot::mechanism::Slider sliderL(&left); static probot::mechanism::Slider sliderR(&right); // Intake/Shooter (no-op); gerçek projede gerçek motorla değiştirin -static probot::motor::NullMotor intakeHW; -static probot::motor::NullMotor shooterHW; -static probot::motor::MotorHandle intake(intakeHW); -static probot::motor::MotorHandle shooter(shooterHW); +static probot::motor::NullMotor intakeMotor; +static probot::motor::NullMotor shooterMotor; // Tuş atamaları (UI tarafındaki buton indeksleri örnektir) static const int BTN_INTAKE_IN = 0; // A @@ -49,16 +46,16 @@ void robotInit(){ } void robotEnd(){ - intake.setPower(0.0f); - shooter.setPower(0.0f); + intakeMotor.setPower(0.0f); + shooterMotor.setPower(0.0f); Serial.println("[FullRobot] robotEnd: Bitti"); } static void handleIntakeAndShooter(const probot::io::joystick_api::Joystick& js){ bool intake_in = js.getRawButton(BTN_INTAKE_IN); bool shoot_btn = js.getRawButton(BTN_SHOOT); - intake.setPower(intake_in ? 0.8f : 0.0f); - shooter.setPower(shoot_btn ? 1.0f : 0.0f); + intakeMotor.setPower(intake_in ? 0.8f : 0.0f); + shooterMotor.setPower(shoot_btn ? 1.0f : 0.0f); } static void handleClimb(const probot::io::joystick_api::Joystick& js){ @@ -113,14 +110,14 @@ void autonomousLoop(){ case 1: if (now - g_autoMs > 3000){ Serial.println("[FullRobot/Auto] 2) Shooter çalıştır"); - shooter.setPower(1.0f); + shooterMotor.setPower(1.0f); g_autoStep=2; g_autoMs=now; } break; case 2: if (now - g_autoMs > 2000){ Serial.println("[FullRobot/Auto] 3) Shooter durdur"); - shooter.setPower(0.0f); + shooterMotor.setPower(0.0f); g_autoStep=3; g_autoMs=now; } break; diff --git a/examples/MotorTest/MotorTest.ino b/examples/MotorTest/MotorTest.ino index 32f1d1f..5bbeae1 100644 --- a/examples/MotorTest/MotorTest.ino +++ b/examples/MotorTest/MotorTest.ino @@ -1,7 +1,6 @@ #include #include #include -#include // Not: Donanımı bağlayana kadar NullMotor kullanabilirsiniz (yer tutucu). // Gerçek projede bu yer tutucuyu gerçek sürücülerle (örn. NFRMotor) değiştirin. // Desteklenen sürücüler için: https://docs.probotstudio.com/ @@ -12,8 +11,7 @@ PROBOT_SET_DRIVER_STATION_PASSWORD("ProBot1234"); -static probot::motor::NullMotor motorHW; // yer tutucu; gerçek sürücü ile değiştirin -static probot::motor::MotorHandle motor(motorHW); // sahipliği içeride yönetir +static probot::motor::NullMotor motor; // yer tutucu; gerçek sürücü ile değiştirin void robotInit() { Serial.println("[MotorTest] robotInit: Motor testi başlıyor"); diff --git a/examples/nfr/AdvancedMecanumDrive/AdvancedMecanumDrive.ino b/examples/nfr/AdvancedMecanumDrive/AdvancedMecanumDrive.ino index 078b0dc..5d44eff 100644 --- a/examples/nfr/AdvancedMecanumDrive/AdvancedMecanumDrive.ino +++ b/examples/nfr/AdvancedMecanumDrive/AdvancedMecanumDrive.ino @@ -1,18 +1,16 @@ #include #include #include -#include #include static probot::motor::NullMotor flHW, frHW, rlHW, rrHW; -static probot::motor::MotorHandle flHandle(flHW), frHandle(frHW), rlHandle(rlHW), rrHandle(rrHW); class NullMotorController : public probot::control::IMotorController { public: - explicit NullMotorController(probot::motor::MotorHandle& handle) : handle_(handle) {} - bool setPower(float power) override { return handle_.underlying().setPower(power); } - void setInverted(bool inv) override { handle_.setInverted(inv); } - bool getInverted() const override { return handle_.getInverted(); } + explicit NullMotorController(probot::motor::IMotorDriver& driver) : driver_(driver) {} + bool setPower(float power) override { return driver_.setPower(power); } + void setInverted(bool inv) override { driver_.setInverted(inv); } + bool getInverted() const override { return driver_.getInverted(); } void setSetpoint(float, probot::controllers::ControlType, int) override {} void setTimeoutMs(uint32_t) override {} void setPidSlotConfig(int, const probot::control::PidConfig&) override {} @@ -29,12 +27,12 @@ public: probot::control::MotionProfileConfig motionProfileConfig() const override { return profileCfg_; } void update(uint32_t, uint32_t) override {} private: - probot::motor::MotorHandle& handle_; + probot::motor::IMotorDriver& driver_; probot::control::MotionProfileType profileType_{probot::control::MotionProfileType::kNone}; probot::control::MotionProfileConfig profileCfg_{}; }; -static NullMotorController fl(flHandle), fr(frHandle), rl(rlHandle), rr(rrHandle); +static NullMotorController fl(flHW), fr(frHW), rl(rlHW), rr(rrHW); static probot::chassis::NfrAdvancedMecanumDrive::Config config; static probot::chassis::NfrAdvancedMecanumDrive chassis(&fl, &fr, &rl, &rr, config); static probot::sensors::imu::Mpu6050 imu; diff --git a/examples/nfr/AdvancedTankDrive/AdvancedTankDrive.ino b/examples/nfr/AdvancedTankDrive/AdvancedTankDrive.ino index d229b92..44ef37f 100644 --- a/examples/nfr/AdvancedTankDrive/AdvancedTankDrive.ino +++ b/examples/nfr/AdvancedTankDrive/AdvancedTankDrive.ino @@ -3,25 +3,22 @@ #include #include #include -#include #include // Example demonstrating the NFRAdvancedTankDrive structure with simulated hardware. static probot::motor::NullMotor leftHW; static probot::motor::NullMotor rightHW; -static probot::motor::MotorHandle leftHandle(leftHW); -static probot::motor::MotorHandle rightHandle(rightHW); - static probot::control::PID pidLeft({0.4f,0.0f,0.0f,-1.0f,1.0f}); static probot::control::PID pidRight({0.4f,0.0f,0.0f,-1.0f,1.0f}); // Null controllers stand in for real motor controllers – swap with real ones on hardware. class NullMotorController : public probot::control::IMotorController { public: - bool setPower(float power) override { return handle_.underlying().setPower(power); } - void setInverted(bool inv) override { handle_.setInverted(inv); } - bool getInverted() const override { return handle_.getInverted(); } + explicit NullMotorController(probot::motor::IMotorDriver& driver) : driver_(driver) {} + bool setPower(float power) override { return driver_.setPower(power); } + void setInverted(bool inv) override { driver_.setInverted(inv); } + bool getInverted() const override { return driver_.getInverted(); } void setSetpoint(float value, probot::control::ControlType mode, int slot = -1) override {} void setTimeoutMs(uint32_t) override {} @@ -38,16 +35,14 @@ public: void setMotionProfileConfig(const probot::control::MotionProfileConfig& cfg) override { profileCfg_ = cfg; } probot::control::MotionProfileConfig motionProfileConfig() const override { return profileCfg_; } void update(uint32_t, uint32_t) override {} - - NullMotorController(probot::motor::MotorHandle& handle) : handle_(handle) {} private: - probot::motor::MotorHandle& handle_; + probot::motor::IMotorDriver& driver_; probot::control::MotionProfileType profileType_{probot::control::MotionProfileType::kNone}; probot::control::MotionProfileConfig profileCfg_{}; }; -static NullMotorController leftController(leftHandle); -static NullMotorController rightController(rightHandle); +static NullMotorController leftController(leftHW); +static NullMotorController rightController(rightHW); static probot::chassis::NfrAdvancedTankDrive::Config config; static probot::chassis::NfrAdvancedTankDrive chassis(&leftController, &rightController, config); diff --git a/src/probot.h b/src/probot.h index f73e385..ab396f7 100644 --- a/src/probot.h +++ b/src/probot.h @@ -18,7 +18,6 @@ #include #include #include -#include #include #include diff --git a/src/probot/devices/motors/motor_handle.hpp b/src/probot/devices/motors/motor_handle.hpp deleted file mode 100644 index cbc9fa5..0000000 --- a/src/probot/devices/motors/motor_handle.hpp +++ /dev/null @@ -1,26 +0,0 @@ -#ifndef PROBOT_DEVICES_MOTORS_MOTOR_HANDLE_HPP -#define PROBOT_DEVICES_MOTORS_MOTOR_HANDLE_HPP -#pragma once -#include - -namespace probot::motor { - -class MotorHandle { -public: - explicit MotorHandle(IMotorDriver& motor) - : _motor(&motor) {} - - void setPower(float value){ _motor->setPower(value); } - void setInverted(bool inv){ _motor->setInverted(inv); } - bool getInverted() const { return _motor->getInverted(); } - - IMotorDriver& underlying() { return *_motor; } - const IMotorDriver& underlying() const { return *_motor; } - -private: - IMotorDriver* _motor; -}; - -} // namespace probot::motor - -#endif // PROBOT_DEVICES_MOTORS_MOTOR_HANDLE_HPP diff --git a/tests/test_devices.cpp b/tests/test_devices.cpp index f8c9728..6ea565e 100644 --- a/tests/test_devices.cpp +++ b/tests/test_devices.cpp @@ -1,7 +1,6 @@ #include "test_harness.hpp" #include -#include #include #include @@ -31,14 +30,13 @@ TEST_CASE(motor_group_power_and_invert){ EXPECT_NEAR(a.lastCommand, 0.4f, 1e-5f); } -TEST_CASE(motor_handle_controls_motor){ +TEST_CASE(null_motor_behaves_like_driver){ probot::motor::NullMotor motor; - probot::motor::MotorHandle handle(motor); - handle.setPower(0.5f); + EXPECT_TRUE(motor.setPower(0.5f)); EXPECT_NEAR(motor.appliedPower(), 0.5f, 1e-5f); - handle.setInverted(true); - EXPECT_TRUE(handle.getInverted()); - handle.setPower(0.2f); + motor.setInverted(true); + EXPECT_TRUE(motor.getInverted()); + EXPECT_TRUE(motor.setPower(0.2f)); EXPECT_NEAR(motor.appliedPower(), -0.2f, 1e-5f); } From f6b9813a07e5c5afcdb5b7a0352c1cbe6c63e6f3 Mon Sep 17 00:00:00 2001 From: tunapro Date: Sat, 18 Oct 2025 21:00:59 +0300 Subject: [PATCH 23/26] examples: replace demos with unified VNH/closed-loop set --- examples/AutonomousDemo/AutonomousDemo.ino | 137 ++++++++++++++++++ examples/BasicTankDrive/BasicTankDrive.ino | 53 ------- .../BoardozaVNHMotorDemo.ino | 113 --------------- .../ClosedLoopMotorTest.ino | 47 ------ examples/EncoderTest/EncoderTest.ino | 32 ---- examples/FullRobotDemo/FullRobotDemo.ino | 135 ----------------- examples/JoystickTest/JoystickTest.ino | 85 +++++++---- .../MecanumDriveDemo/MecanumDriveDemo.ino | 110 ++++++++++++++ .../MotorControllerDemo.ino | 87 +++++++++++ examples/MotorDriverDemo/MotorDriverDemo.ino | 71 +++++++++ examples/MotorTest/MotorTest.ino | 42 ------ examples/ShooterDemo/ShooterDemo.ino | 83 +++++++++++ examples/SliderDemo/SliderDemo.ino | 97 +++++++++++++ examples/SliderTest/SliderTest.ino | 58 -------- examples/TankDriveAuto/TankDriveAuto.ino | 44 ------ examples/TankDriveDemo/TankDriveDemo.ino | 118 +++++++++++++++ examples/TurretDemo/TurretDemo.ino | 100 +++++++++++++ examples/__library_impl/.gitkeep | 1 - examples/__library_impl/Basic/Basic.ino | 45 ------ .../ClosedLoopDemo/ClosedLoopDemo.ino | 64 -------- .../DriverStationDemo/DriverStationDemo.ino | 18 --- .../LoopPeriodStress/LoopPeriodStress.ino | 10 -- .../RGBClosedLoop/RGBClosedLoop.ino | 10 -- .../__library_impl/TestSlider/TestSlider.ino | 44 ------ .../TestTankDrive/TestTankDrive.ino | 59 -------- .../AdvancedMecanumDrive.ino | 75 ---------- .../AdvancedTankDrive/AdvancedTankDrive.ino | 87 ----------- 27 files changed, 856 insertions(+), 969 deletions(-) create mode 100644 examples/AutonomousDemo/AutonomousDemo.ino delete mode 100644 examples/BasicTankDrive/BasicTankDrive.ino delete mode 100644 examples/BoardozaVNHMotorDemo/BoardozaVNHMotorDemo.ino delete mode 100644 examples/ClosedLoopMotorTest/ClosedLoopMotorTest.ino delete mode 100644 examples/EncoderTest/EncoderTest.ino delete mode 100644 examples/FullRobotDemo/FullRobotDemo.ino create mode 100644 examples/MecanumDriveDemo/MecanumDriveDemo.ino create mode 100644 examples/MotorControllerDemo/MotorControllerDemo.ino create mode 100644 examples/MotorDriverDemo/MotorDriverDemo.ino delete mode 100644 examples/MotorTest/MotorTest.ino create mode 100644 examples/ShooterDemo/ShooterDemo.ino create mode 100644 examples/SliderDemo/SliderDemo.ino delete mode 100644 examples/SliderTest/SliderTest.ino delete mode 100644 examples/TankDriveAuto/TankDriveAuto.ino create mode 100644 examples/TankDriveDemo/TankDriveDemo.ino create mode 100644 examples/TurretDemo/TurretDemo.ino delete mode 100644 examples/__library_impl/.gitkeep delete mode 100644 examples/__library_impl/Basic/Basic.ino delete mode 100644 examples/__library_impl/ClosedLoopDemo/ClosedLoopDemo.ino delete mode 100644 examples/__library_impl/DriverStationDemo/DriverStationDemo.ino delete mode 100644 examples/__library_impl/LoopPeriodStress/LoopPeriodStress.ino delete mode 100644 examples/__library_impl/RGBClosedLoop/RGBClosedLoop.ino delete mode 100644 examples/__library_impl/TestSlider/TestSlider.ino delete mode 100644 examples/__library_impl/TestTankDrive/TestTankDrive.ino delete mode 100644 examples/nfr/AdvancedMecanumDrive/AdvancedMecanumDrive.ino delete mode 100644 examples/nfr/AdvancedTankDrive/AdvancedTankDrive.ino diff --git a/examples/AutonomousDemo/AutonomousDemo.ino b/examples/AutonomousDemo/AutonomousDemo.ino new file mode 100644 index 0000000..1da665d --- /dev/null +++ b/examples/AutonomousDemo/AutonomousDemo.ino @@ -0,0 +1,137 @@ +#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/BasicTankDrive/BasicTankDrive.ino b/examples/BasicTankDrive/BasicTankDrive.ino deleted file mode 100644 index 0fe0990..0000000 --- a/examples/BasicTankDrive/BasicTankDrive.ino +++ /dev/null @@ -1,53 +0,0 @@ -#include -#include -#include -#include -// Not: Donanımı bağlayana kadar NullMotor/TestEncoder kullanabilirsiniz (yer tutucu). -// Gerçek projede bu yer tutucuları gerçek sürücülerle (örn. NFRMotor) değiştirin. -// Desteklenen sürücüler için: https://docs.probotstudio.com/ - -// Bu örnek, tank şasi (BasicTankDrive) ile teleop sürüşünü gösterir. -// Sol çubuk Y sol teker, sağ çubuk Y sağ teker hızını belirler. - -PROBOT_SET_DRIVER_STATION_PASSWORD("ProBot1234"); - -static const probot::control::PidConfig kPidCfg{ .kp=0.2f, .ki=0.0f, .kd=0.0f, .kf=0.0f, .out_min=-1.0f, .out_max=1.0f }; -static probot::control::PID pidL(kPidCfg), pidR(kPidCfg); -static probot::sensors::TestEncoder leftEnc, rightEnc; // yer tutucu -static probot::motor::NullMotor leftHW, rightHW; // yer tutucu -static probot::control::ClosedLoopMotor left(&leftEnc, &pidL, &leftHW, 1.0f, 1.0f); -static probot::control::ClosedLoopMotor right(&rightEnc, &pidR, &rightHW, 1.0f, 1.0f); -static probot::drive::BasicTankDrive chassis(&left, &right); - -void robotInit() { - Serial.println("[TankTeleop] robotInit: Tank sürüşü"); - // Örnek bağlama (gerçek sürücüler ile değiştirin): - // chassis.setWheelCircumference(31.4f); - // chassis.setTrackWidth(25.0f); -} - -void robotEnd() { - Serial.println("[TankTeleop] robotEnd: Bitti"); -} - -void teleopInit() { - // Mapping değiştirmek için (varsayılan: "logitech-f310"): - // probot::io::joystick_mapping::setActiveByName("standard"); - // probot::io::joystick_mapping::setActiveByName("logitech-f310"); - // probot::io::joystick_mapping::setActiveByName("axis9-dpad"); - Serial.println("[TankTeleop] teleopInit: Joystick ile tank sürüş"); -} - -void teleopLoop() { - auto js = probot::io::joystick_api::makeDefault(); - float left_axis = js.getLeftY(); // sol Y - float right_axis = js.getRightY(); // sağ Y - - float max_vel = 100.0f; // birim/s örnek - chassis.setVelocity(left_axis*max_vel, right_axis*max_vel); - chassis.update(millis(), 20); - delay(20); -} - -void autonomousInit() {} -void autonomousLoop() { delay(1000); } diff --git a/examples/BoardozaVNHMotorDemo/BoardozaVNHMotorDemo.ino b/examples/BoardozaVNHMotorDemo/BoardozaVNHMotorDemo.ino deleted file mode 100644 index 36a7188..0000000 --- a/examples/BoardozaVNHMotorDemo/BoardozaVNHMotorDemo.ino +++ /dev/null @@ -1,113 +0,0 @@ -/* - Boardoza VNH Motor Demo (Joystick Kontrollü) - -------------------------------------------- - Bu örnek, VNH5019 tabanlı Boardoza motor sürücüsünü Probot Driver Station - joystick verisiyle nasıl sürebileceğinizi gösterir. - - Adımlar: - 1. Aşağıdaki pin tanımlarını kendi kartınıza göre düzenleyin. - 2. Şifreyi (en az 8 karakter) değiştirin ve kaydedin. - 3. S3 kartınızı çalıştırın, bilgisayardan Probot-XXXX ağına bağlanın. - 4. Tarayıcıdan 192.168.4.1 adresine gidip joystick’i hareket ettirin. - 5. Joystick Y ekseni (varsayılan: axes[1]) motora -1..1 arasında güç gönderir. - - Notlar: - - Sürücü her zaman fren modunda bekler. Joystick bırakıldığında motor sıkı durur. - - Joystick ölçeği -1..1 olduğundan Probot motor gücüyle birebir uyumludur. - - `GamepadSnapshot` eksen sırası driver station’daki girişe göre değişebilir. - Gerekirse `AXIS_INDEX` sabitini uyarlayın (örn. 0 veya 3). -*/ - -#include -#include - -// --- Motor sürücü pinleri (kartınızın bağlantısına göre değiştirin) --- -static constexpr int PIN_INA = 47; -static constexpr int PIN_INB = 46; -static constexpr int PIN_PWM = 48; -static constexpr int PIN_ENA = -1; // ENA pini 3V3'e bağlıysa -1 bırakın -static constexpr int PIN_ENB = -1; // ENB pini 3V3'e bağlıysa -1 bırakın - -// Joystick ekseni: çoğu gamepad'de 1 = sol çubuğun Y ekseni -static constexpr uint8_t AXIS_INDEX = 1; -static constexpr float DEADZONE = 0.05f; // küçük titreşimleri yok say - -// Driver Station erişimi için şifre (minimum 8 karakter) -PROBOT_SET_DRIVER_STATION_PASSWORD("ProBot1234"); - -// Motor nesnemiz ve kontrol sapı -static probot::motor::BoardozaVNHMotorDriver g_motor( - PIN_INA, - PIN_INB, - PIN_PWM, - PIN_ENA, - PIN_ENB -); -static float g_lastReportedPower = 0.0f; - -static float applyDeadband(float value){ - if (std::fabs(value) < DEADZONE) return 0.0f; - return value; -} - -static float clampUnit(float v){ - if (v > 1.0f) return 1.0f; - if (v < -1.0f) return -1.0f; - return v; -} - -// --- Probot yaşam döngüsü fonksiyonları --- -void robotInit(){ - Serial.begin(115200); - delay(100); - Serial.println("[BoardozaVNH] Demo starting (20 kHz PWM, brake mode)"); - g_motor.begin(); - g_motor.setBrakeMode(true); // boşta tam fren - g_motor.setBrakeStrength(1.0f); // PWM %100 ile fren uygula - g_motor.setPower(0.0f); - g_lastReportedPower = 0.0f; -} - -void robotEnd(){ - g_motor.setPower(0.0f); - Serial.println("[BoardozaVNH] Demo stopped"); -} - -void teleopInit(){ - g_motor.setPower(0.0f); - g_lastReportedPower = 0.0f; -} - -void teleopLoop(){ - auto snapshot = probot::io::gamepad().read(); - - float power = 0.0f; - if (snapshot.axisCount > AXIS_INDEX){ - power = clampUnit(snapshot.axes[AXIS_INDEX]); - power = -power; // Logitech tabanlı gamepadlerde ileri hareket pozitif olsun - power = applyDeadband(power); - } - - g_motor.setPower(power); - - // İsteğe bağlı: bir düğmeye basıldığında yönü ters çevirmek - /* - if (snapshot.buttonCount > 0 && snapshot.buttons[0]){ - g_motor.setInverted(true); - } else { - g_motor.setInverted(false); - } - */ - - if (std::fabs(power - g_lastReportedPower) > 0.02f){ - Serial.printf("[BoardozaVNH] Power command: %.2f (seq=%lu)\n", - static_cast(power), - static_cast(snapshot.seq)); - g_lastReportedPower = power; - } - - delay(10); // 100 Hz kontrol döngüsü -} - -void autonomousInit(){} -void autonomousLoop(){} diff --git a/examples/ClosedLoopMotorTest/ClosedLoopMotorTest.ino b/examples/ClosedLoopMotorTest/ClosedLoopMotorTest.ino deleted file mode 100644 index 9b3990e..0000000 --- a/examples/ClosedLoopMotorTest/ClosedLoopMotorTest.ino +++ /dev/null @@ -1,47 +0,0 @@ -#include -#include -#include -#include -// Not: Donanımı bağlayana kadar NullMotor/TestEncoder kullanabilirsiniz (yer tutucu). -// Gerçek projede bu yer tutucuları gerçek sürücülerle (örn. NFRMotor) değiştirin. -// Desteklenen sürücüler için: https://docs.probotstudio.com/ - -// Bu örnek, kapalı çevrim (ClosedLoopMotor) bir motoru joystick ile sürer. -// Sol çubuk Y ekseni hız referansı, D-Pad (ör. butonlar) ise mod geçişi gibi kullanılabilir. - -PROBOT_SET_DRIVER_STATION_PASSWORD("ProBot1234"); - -static probot::sensors::TestEncoder encoderHW; // yer tutucu -static probot::motor::NullMotor motorHW; // yer tutucu -static const probot::control::PidConfig kPidCfg{ .kp=0.2f, .ki=0.0f, .kd=0.0f, .kf=0.0f, .out_min=-1.0f, .out_max=1.0f }; -static probot::control::PID pid(kPidCfg); -static probot::control::ClosedLoopMotor clm(&encoderHW, &pid, &motorHW, 1.0f, 1.0f); - -void robotInit() { - Serial.println("[CLMTest] robotInit: ClosedLoopMotor testi"); -} - -void robotEnd() { - Serial.println("[CLMTest] robotEnd: Bitti"); -} - -void teleopInit() { - // Mapping değiştirmek için (varsayılan: "logitech-f310"): - // probot::io::joystick_mapping::setActiveByName("standard"); - // probot::io::joystick_mapping::setActiveByName("logitech-f310"); - // probot::io::joystick_mapping::setActiveByName("axis9-dpad"); - Serial.println("[CLMTest] teleopInit: Joystick ile hız/konum kontrolü"); -} - -void teleopLoop() { - auto js = probot::io::joystick_api::makeDefault(); - float axis = js.getLeftY(); // sol çubuk Y - float vel_ref = axis * 100.0f; // örnek: 100 birim/s maksimum hız - clm.setSetpoint(vel_ref, probot::control::ControlType::kVelocity); - clm.update(millis(), 20); - Serial.printf("[CLMTest] vel_ref=%.2f\n", vel_ref); - delay(20); -} - -void autonomousInit() {} -void autonomousLoop() { delay(1000); } diff --git a/examples/EncoderTest/EncoderTest.ino b/examples/EncoderTest/EncoderTest.ino deleted file mode 100644 index 7b794ed..0000000 --- a/examples/EncoderTest/EncoderTest.ino +++ /dev/null @@ -1,32 +0,0 @@ -#include -#include - -// Bu örnek, enkoder değerlerini (tik ve hız) Serial Monitör'e yazdırır. -// Donanımı bağlayana kadar TestEncoder kullanabilirsiniz (yer tutucu). -// Gerçek projede bu yer tutucuyu gerçek enkoder sürücüsüyle değiştirin. - -PROBOT_SET_DRIVER_STATION_PASSWORD("ProBot1234"); - -static probot::sensors::TestEncoder encoderHW; // yer tutucu; gerçek sürücü ile değiştirin - -void robotInit() { - Serial.println("[EncoderTest] robotInit: Enkoder testi"); -} - -void robotEnd() { - Serial.println("[EncoderTest] robotEnd: Bitti"); -} - -void teleopInit() { - Serial.println("[EncoderTest] teleopInit: Enkoder değerleri yazdırılacak"); -} - -void teleopLoop() { - int32_t ticks = encoderHW.readTicks(); - int32_t tps = encoderHW.readTicksPerSecond(); - Serial.printf("[EncoderTest] ticks=%ld tps=%ld\n", (long)ticks, (long)tps); - delay(200); -} - -void autonomousInit() {} -void autonomousLoop() { delay(1000); } \ No newline at end of file diff --git a/examples/FullRobotDemo/FullRobotDemo.ino b/examples/FullRobotDemo/FullRobotDemo.ino deleted file mode 100644 index 5884c06..0000000 --- a/examples/FullRobotDemo/FullRobotDemo.ino +++ /dev/null @@ -1,135 +0,0 @@ -#include -#include -#include -#include - -// Bu örnek, daha tamamlanmış bir robot iskeleti gösterir: -// - TankDrive şasi (teleop + otonom) -// - Intake (içeri alma) ve Shooter (fırlatma) -// - İki adet Slider ile tırmanma mekanizması (aç/kapa senaryosu) -// Not: NullMotor/TestEncoder yer tutucu (no-op) sürücülerdir. -// Gerçek projede bunları gerçek sürücülerle (örn. NFRMotor) değiştirin. -// Desteklenen motorlar için: https://docs.probotstudio.com/ - -PROBOT_SET_DRIVER_STATION_PASSWORD("ProBot1234"); - -// --- Dosya-üstü kurulum (sıralı, güvenli) --- -static const probot::control::PidConfig kPidCfg{ .kp=0.2f, .ki=0.0f, .kd=0.0f, .kf=0.0f, .out_min=-1.0f, .out_max=1.0f }; -static probot::control::PID pidL(kPidCfg), pidR(kPidCfg); -static probot::sensors::TestEncoder leftEnc, rightEnc; // yer tutucu -static probot::motor::NullMotor leftHW, rightHW; // yer tutucu -static probot::control::ClosedLoopMotor left(&leftEnc, &pidL, &leftHW, 1.0f, 1.0f); -static probot::control::ClosedLoopMotor right(&rightEnc, &pidR, &rightHW, 1.0f, 1.0f); -static probot::drive::BasicTankDrive chassis(&left, &right); - -// Tırmanma sliderları (örnek amaçlı aynı motor/encoder ile) -static probot::mechanism::Slider sliderL(&left); -static probot::mechanism::Slider sliderR(&right); - -// Intake/Shooter (no-op); gerçek projede gerçek motorla değiştirin -static probot::motor::NullMotor intakeMotor; -static probot::motor::NullMotor shooterMotor; - -// Tuş atamaları (UI tarafındaki buton indeksleri örnektir) -static const int BTN_INTAKE_IN = 0; // A -static const int BTN_SHOOT = 1; // B -static const int BTN_CLIMB_OPEN = 8; // LB -static const int BTN_CLIMB_CLOSE = 9; // LT - -// Otonom senaryo adımları -static uint32_t g_autoStep = 0; -static uint32_t g_autoMs = 0; - -void robotInit(){ - Serial.println("[FullRobot] robotInit: Başlatılıyor"); - // Örn: chassis.setWheelCircumference(31.4f); chassis.setTrackWidth(25.0f); -} - -void robotEnd(){ - intakeMotor.setPower(0.0f); - shooterMotor.setPower(0.0f); - Serial.println("[FullRobot] robotEnd: Bitti"); -} - -static void handleIntakeAndShooter(const probot::io::joystick_api::Joystick& js){ - bool intake_in = js.getRawButton(BTN_INTAKE_IN); - bool shoot_btn = js.getRawButton(BTN_SHOOT); - intakeMotor.setPower(intake_in ? 0.8f : 0.0f); - shooterMotor.setPower(shoot_btn ? 1.0f : 0.0f); -} - -static void handleClimb(const probot::io::joystick_api::Joystick& js){ - bool open = js.getRawButton(BTN_CLIMB_OPEN); - bool close = js.getRawButton(BTN_CLIMB_CLOSE); - - if (open){ - sliderL.setTargetLength(40.0f); sliderR.setTargetLength(40.0f); - uint32_t t0 = millis(); while (millis()-t0 < 2000){ sliderL.update(millis(), 20); sliderR.update(millis(), 20); delay(20);} - sliderL.setTargetLength(0.0f); sliderR.setTargetLength(0.0f); - } - if (close){ - sliderL.setTargetLength(0.0f); sliderR.setTargetLength(0.0f); - } - - sliderL.update(millis(), 20); - sliderR.update(millis(), 20); -} - -void teleopInit(){ - // Mapping değiştirmek için (varsayılan: "logitech-f310"): - // probot::io::joystick_mapping::setActiveByName("standard"); - // probot::io::joystick_mapping::setActiveByName("logitech-f310"); - // probot::io::joystick_mapping::setActiveByName("axis9-dpad"); - Serial.println("[FullRobot] teleopInit: Tank sürüş + intake/shooter + climb"); -} - -void teleopLoop(){ - auto js = probot::io::joystick_api::makeDefault(); - float left_axis = js.getLeftY(); - float right_axis = js.getRightY(); - float max_vel = 100.0f; - chassis.setVelocity(left_axis*max_vel, right_axis*max_vel); - chassis.update(millis(), 20); - handleIntakeAndShooter(js); - handleClimb(js); - delay(20); -} - -void autonomousInit(){ - Serial.println("[FullRobot] autonomousInit: Otonom başlayacak"); - g_autoStep = 0; g_autoMs = millis(); -} - -void autonomousLoop(){ - uint32_t now = millis(); - switch (g_autoStep){ - case 0: - Serial.println("[FullRobot/Auto] 1) 50 cm ileri"); - chassis.driveDistance(50.0f); - g_autoStep=1; g_autoMs=now; break; - case 1: - if (now - g_autoMs > 3000){ - Serial.println("[FullRobot/Auto] 2) Shooter çalıştır"); - shooterMotor.setPower(1.0f); - g_autoStep=2; g_autoMs=now; - } - break; - case 2: - if (now - g_autoMs > 2000){ - Serial.println("[FullRobot/Auto] 3) Shooter durdur"); - shooterMotor.setPower(0.0f); - g_autoStep=3; g_autoMs=now; - } - break; - case 3: - if (now - g_autoMs > 500){ - Serial.println("[FullRobot/Auto] 4) 30 cm ileri"); - chassis.driveDistance(30.0f); - g_autoStep=4; g_autoMs=now; - } - break; - default: - break; - } - delay(20); -} diff --git a/examples/JoystickTest/JoystickTest.ino b/examples/JoystickTest/JoystickTest.ino index b411999..a932644 100644 --- a/examples/JoystickTest/JoystickTest.ino +++ b/examples/JoystickTest/JoystickTest.ino @@ -1,51 +1,72 @@ #include #include +#include +#include +#include -// Bu örnek, web arayüzünden gelen joystick verilerini okuyup -// Serial Monitör'e yazdırır. -// Not: Artık joystick verisi her durumda gönderilir. +// 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"); void robotInit() { - Serial.println("[JoystickTest] robotInit: Başlatılıyor"); + 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ı"); } void robotEnd() { - Serial.println("[JoystickTest] robotEnd: Bitti"); + controller.setPowerDirect(0.0f); // çıkışları güvenle sıfırla + Serial.println("[JoystickTest] robotEnd: Motor sıfırlandı"); } void teleopInit() { - // Mapping değiştirmek için (varsayılan: "logitech-f310"): - // probot::io::joystick_mapping::setActiveByName("standard"); - // probot::io::joystick_mapping::setActiveByName("logitech-f310"); - // probot::io::joystick_mapping::setActiveByName("axis9-dpad"); - Serial.println("[JoystickTest] teleopInit: Yeni joystick_api ile test"); + Serial.println("[JoystickTest] teleopInit: Ekseni okuyup motora aktaracağız"); } void teleopLoop() { auto js = probot::io::joystick_api::makeDefault(); - Serial.printf("[JoystickTest] seq=%lu axes=%lu buttons=%lu\n", - (unsigned long)js.getSeq(), - (unsigned long)js.getAxisCount(), - (unsigned long)js.getButtonCount()); - - Serial.printf(" L(%.2f, %.2f) R(%.2f, %.2f) LT=%.0f RT=%.0f POV=%d\n", - js.getLeftX(), js.getLeftY(), - js.getRightX(), js.getRightY(), - js.getLeftTriggerAxis(), js.getRightTriggerAxis(), - js.getPOV()); - - // Ham eksen/tuş örneği - if (js.getAxisCount() > 0) { - Serial.printf(" raw axis[0]=%.2f\n", js.getRawAxis(0)); - } - if (js.getButtonCount() > 0) { - Serial.printf(" raw button[0]=%s\n", js.getRawButton(0) ? "ON" : "OFF"); - } - - delay(150); + + // Sol çubuk Y eksenini oku (varsayılan eşleme). + float axis = js.getLeftY(); + + // Okuduğumuz değeri doğrudan motora gönderiyoruz. + controller.setPowerDirect(axis); + + // 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()); + + delay(50); } -void autonomousInit() {} -void autonomousLoop() { delay(1000); } \ No newline at end of file +void autonomousInit() { + Serial.println("[JoystickTest] autonomousInit: Bu örnek otonomda motoru durdurur"); + controller.setPowerDirect(0.0f); +} + +void autonomousLoop() { + // Joystick okumadığımız için otonomda motoru sıfırda tutuyoruz. + controller.update(millis(), 20); + delay(20); +} diff --git a/examples/MecanumDriveDemo/MecanumDriveDemo.ino b/examples/MecanumDriveDemo/MecanumDriveDemo.ino new file mode 100644 index 0000000..d38ce88 --- /dev/null +++ b/examples/MecanumDriveDemo/MecanumDriveDemo.ino @@ -0,0 +1,110 @@ +#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 new file mode 100644 index 0000000..e975818 --- /dev/null +++ b/examples/MotorControllerDemo/MotorControllerDemo.ino @@ -0,0 +1,87 @@ +#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 new file mode 100644 index 0000000..625166e --- /dev/null +++ b/examples/MotorDriverDemo/MotorDriverDemo.ino @@ -0,0 +1,71 @@ +#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/MotorTest/MotorTest.ino b/examples/MotorTest/MotorTest.ino deleted file mode 100644 index 5bbeae1..0000000 --- a/examples/MotorTest/MotorTest.ino +++ /dev/null @@ -1,42 +0,0 @@ -#include -#include -#include -// Not: Donanımı bağlayana kadar NullMotor kullanabilirsiniz (yer tutucu). -// Gerçek projede bu yer tutucuyu gerçek sürücülerle (örn. NFRMotor) değiştirin. -// Desteklenen sürücüler için: https://docs.probotstudio.com/ - -// Bu örnek, joystick'ten gelen bir eksen değerini (-1..1) -// ham motor gücüne (normalize -1..1) direkt olarak eşler. -// Amaç: Motor bağlantısını test etmek ve yön/invert kontrolünü doğrulamak. - -PROBOT_SET_DRIVER_STATION_PASSWORD("ProBot1234"); - -static probot::motor::NullMotor motor; // yer tutucu; gerçek sürücü ile değiştirin - -void robotInit() { - Serial.println("[MotorTest] robotInit: Motor testi başlıyor"); -} - -void robotEnd() { - motor.setPower(0.0f); - Serial.println("[MotorTest] robotEnd: Bitti"); -} - -void teleopInit() { - // Mapping değiştirmek için (varsayılan: "logitech-f310"): - // probot::io::joystick_mapping::setActiveByName("standard"); - // probot::io::joystick_mapping::setActiveByName("logitech-f310"); - // probot::io::joystick_mapping::setActiveByName("axis9-dpad"); - Serial.println("[MotorTest] teleopInit: Joystick ekseni motora güç olarak yazılacak"); -} - -void teleopLoop() { - auto js = probot::io::joystick_api::makeDefault(); - float axis = js.getLeftY(); // Örn: sol çubuk Y - motor.setPower(axis); - Serial.printf("[MotorTest] axis=%.2f power=%.2f\n", axis, axis); - delay(50); -} - -void autonomousInit() {} -void autonomousLoop() { delay(1000); } diff --git a/examples/ShooterDemo/ShooterDemo.ino b/examples/ShooterDemo/ShooterDemo.ino new file mode 100644 index 0000000..7a69c92 --- /dev/null +++ b/examples/ShooterDemo/ShooterDemo.ino @@ -0,0 +1,83 @@ +#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 new file mode 100644 index 0000000..2263d28 --- /dev/null +++ b/examples/SliderDemo/SliderDemo.ino @@ -0,0 +1,97 @@ +#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/SliderTest/SliderTest.ino b/examples/SliderTest/SliderTest.ino deleted file mode 100644 index 3414614..0000000 --- a/examples/SliderTest/SliderTest.ino +++ /dev/null @@ -1,58 +0,0 @@ -#include -#include -#include -#include -// Not: Donanımı bağlayana kadar NullMotor/TestEncoder kullanabilirsiniz (yer tutucu). -// Gerçek projede bu yer tutucuları gerçek sürücülerle (örn. NFRMotor) değiştirin. -// Desteklenen sürücüler için: https://docs.probotstudio.com/ - -// Bu örnek, Slider nesnesini D-Pad ile 10/20/30/40 cm hedeflerine taşımayı dener. -// Slider, bir ClosedLoopMotor üzerinden konum modunda sürülür. - -PROBOT_SET_DRIVER_STATION_PASSWORD("ProBot1234"); - -static const probot::control::PidConfig kPidCfg{ .kp=0.2f, .ki=0.0f, .kd=0.0f, .kf=0.0f, .out_min=-1.0f, .out_max=1.0f }; -static probot::control::PID pid(kPidCfg); -static probot::sensors::TestEncoder encHW; // yer tutucu -static probot::motor::NullMotor motHW; // yer tutucu -static probot::control::ClosedLoopMotor clm(&encHW, &pid, &motHW, 1.0f, 1.0f); -static probot::mechanism::Slider slider(&clm); - -void robotInit() { - Serial.println("[SliderTest] robotInit: Slider testi"); - // slider.setLengthToTicks(...); -} - -void robotEnd() { - Serial.println("[SliderTest] robotEnd: Bitti"); -} - -void teleopInit() { - // Mapping değiştirmek için (varsayılan: "logitech-f310"): - // probot::io::joystick_mapping::setActiveByName("standard"); - // probot::io::joystick_mapping::setActiveByName("logitech-f310"); - // probot::io::joystick_mapping::setActiveByName("axis9-dpad"); - Serial.println("[SliderTest] teleopInit: D-Pad ile 10/20/30/40 cm hedefleri"); -} - -void teleopLoop() { - auto js = probot::io::joystick_api::makeDefault(); - - // Basit D-Pad: Up/Down/Left/Right (POV 0/180/270/90) - int pov = js.getPOV(); - bool up = (pov == 0); - bool down = (pov == 180); - bool left = (pov == 270); - bool right = (pov == 90); - - if (up) { slider.setTargetLength(10.0f); Serial.println("[SliderTest] Hedef: 10 cm"); } - if (down) { slider.setTargetLength(20.0f); Serial.println("[SliderTest] Hedef: 20 cm"); } - if (left) { slider.setTargetLength(30.0f); Serial.println("[SliderTest] Hedef: 30 cm"); } - if (right) { slider.setTargetLength(40.0f); Serial.println("[SliderTest] Hedef: 40 cm"); } - - slider.update(millis(), 20); - delay(20); -} - -void autonomousInit() {} -void autonomousLoop() { delay(1000); } diff --git a/examples/TankDriveAuto/TankDriveAuto.ino b/examples/TankDriveAuto/TankDriveAuto.ino deleted file mode 100644 index 95911f4..0000000 --- a/examples/TankDriveAuto/TankDriveAuto.ino +++ /dev/null @@ -1,44 +0,0 @@ -#include -#include -#include -#include - -// Bu örnek, tank sürüş şasesi için basit bir otonom senaryoyu gösterir. -// Sırasıyla: X cm ileri git, Y derece dön, tekrar X cm ileri git gibi bir akış. -// driveDistance ve turnDegrees komutları konum hedeflerini gönderir. - -PROBOT_SET_DRIVER_STATION_PASSWORD("ProBot1234"); - -static const probot::control::PidConfig kPidCfg{ .kp=0.2f, .ki=0.0f, .kd=0.0f, .kf=0.0f, .out_min=-1.0f, .out_max=1.0f }; -static probot::control::PID pidL(kPidCfg), pidR(kPidCfg); -static probot::sensors::TestEncoder leftEnc, rightEnc; -static probot::motor::NullMotor leftHW, rightHW; -static probot::control::ClosedLoopMotor left(&leftEnc, &pidL, &leftHW, 1.0f, 1.0f); -static probot::control::ClosedLoopMotor right(&rightEnc, &pidR, &rightHW, 1.0f, 1.0f); -static probot::drive::BasicTankDrive chassis(&left, &right); - -static uint32_t g_step = 0; -static uint32_t g_last_ms = 0; - -void robotInit() { - Serial.println("[TankAuto] robotInit"); - // chassis.setWheelCircumference(...); chassis.setTrackWidth(...); -} - -void robotEnd() { Serial.println("[TankAuto] robotEnd"); } - -void teleopInit() { Serial.println("[TankAuto] teleopInit"); } -void teleopLoop() { - auto js = probot::io::joystick_api::makeDefault(); - float left_axis = js.getLeftY(); - float right_axis = js.getRightY(); - chassis.setVelocity(left_axis*100.0f, right_axis*100.0f); - chassis.update(millis(), 20); - delay(20); -} - -void autonomousInit() { Serial.println("[TankAuto] autonomousInit"); } -void autonomousLoop() { - chassis.driveDistance(50.0f); - delay(1000); -} diff --git a/examples/TankDriveDemo/TankDriveDemo.ino b/examples/TankDriveDemo/TankDriveDemo.ino new file mode 100644 index 0000000..9225314 --- /dev/null +++ b/examples/TankDriveDemo/TankDriveDemo.ino @@ -0,0 +1,118 @@ +#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 new file mode 100644 index 0000000..25e248f --- /dev/null +++ b/examples/TurretDemo/TurretDemo.ino @@ -0,0 +1,100 @@ +#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/__library_impl/.gitkeep b/examples/__library_impl/.gitkeep deleted file mode 100644 index 0519ecb..0000000 --- a/examples/__library_impl/.gitkeep +++ /dev/null @@ -1 +0,0 @@ - \ No newline at end of file diff --git a/examples/__library_impl/Basic/Basic.ino b/examples/__library_impl/Basic/Basic.ino deleted file mode 100644 index 01e03c3..0000000 --- a/examples/__library_impl/Basic/Basic.ino +++ /dev/null @@ -1,45 +0,0 @@ -#include - -static probot::control::BlinkPid* g_pid = nullptr; - -void robotInit() { - Serial.printf("[USER ] robotInit (core %d)\n", xPortGetCoreID()); -} - -void robotEnd() { - Serial.printf("[USER ] robotEnd (core %d)\n", xPortGetCoreID()); -} - -void teleopInit() { - static probot::control::BlinkPid pid_instance; // program ömrü boyunca - g_pid = &pid_instance; - control::setGlobalPeriodMs(20); - control::attach(g_pid); - Serial.println("[USER ] teleopInit: BlinkPid attached (20 ms global)"); -} - -void teleopLoop() { - uint32_t last_sec = joystick::get_ms() / 1000u; - while (true) { - uint32_t ms = joystick::get_ms(); - uint32_t sec = ms / 1000u; - if (sec != last_sec && g_pid){ - last_sec = sec; - g_pid->setReference(sec); - Serial.printf("[USER] setReference(sec=%lu)\n", (unsigned long)sec); - } - auto js = joystick::read(); - Serial.printf("[USER/teleopLoop] seq=%lu ms=%lums (core %d)\n", - (unsigned long)js.seq, (unsigned long)js.ms, xPortGetCoreID()); - delay(500); - } -} - -void autonomousInit() { - Serial.printf("[USER ] autonomousInit (core %d)\n", xPortGetCoreID()); -} - -void autonomousLoop() { - Serial.printf("[USER ] autonomousLoop (core %d)\n", xPortGetCoreID()); - delay(1000); -} diff --git a/examples/__library_impl/ClosedLoopDemo/ClosedLoopDemo.ino b/examples/__library_impl/ClosedLoopDemo/ClosedLoopDemo.ino deleted file mode 100644 index ae3f5f7..0000000 --- a/examples/__library_impl/ClosedLoopDemo/ClosedLoopDemo.ino +++ /dev/null @@ -1,64 +0,0 @@ -#include - -// TestClosedLoopDemo -// Demonstrates ClosedLoopMotor with simulated components - -static probot::test::TestMotor g_motor; -static probot::test::TestEncoder g_encoder; -static probot::control::PidConfig g_cfg_vel{ 0.0008f, 0.0004f, 0.0f, 0.0f, -1.0f, 1.0f }; -static probot::control::PID g_pid(g_cfg_vel); -static probot::control::ClosedLoopMotor* g_axis = nullptr; -static probot::test::TestPlant* g_plant = nullptr; - -class LedVisualizer : public control::IUpdatable { -public: - LedVisualizer(probot::sensors::IEncoder* enc, float full_scale_tps) - : enc_(enc), full_scale_tps_(full_scale_tps) {} - void update(uint32_t now_ms, uint32_t dt_ms) override { - (void)now_ms; (void)dt_ms; - int32_t tps = enc_ ? enc_->readTicksPerSecond() : 0; - if (tps < 0) tps = -tps; - float x = (float)tps / (full_scale_tps_ > 1.0f ? full_scale_tps_ : 1.0f); - if (x > 1.0f) x = 1.0f; - uint8_t br = (uint8_t)(x * 255.0f); - probot::builtinled::setBrightness(br); - probot::builtinled::set(true); - } -private: - probot::sensors::IEncoder* enc_; - float full_scale_tps_; -}; - -static LedVisualizer* g_ledviz = nullptr; - -void robotInit() {} -void robotEnd() {} - -void teleopInit() { - static probot::control::ClosedLoopMotor axis(&g_encoder, &g_pid, &g_motor, 1.0f, 1.0f); - g_axis = &axis; - - g_axis->setPidSlotConfig(0, g_cfg_vel); - g_axis->selectDefaultSlot(probot::control::ControlType::kVelocity, 0); - - g_motor.setInverted(false); - - static probot::test::TestPlant plant(&g_motor, &g_encoder); - g_plant = &plant; - - static LedVisualizer ledviz(&g_encoder, 400.0f); // full brightness at ~400 tps - g_ledviz = &ledviz; - - control::setGlobalPeriodMs(20); - control::attach(g_axis); - control::attach(g_plant); - control::attach(g_ledviz); - - Serial.println("[DEMO ] teleopInit: ClosedLoop + Plant + LED attached (20 ms)"); -} - -void teleopLoop() { delay(500); } - -void autonomousInit() {} - -void autonomousLoop() { delay(1000); } diff --git a/examples/__library_impl/DriverStationDemo/DriverStationDemo.ino b/examples/__library_impl/DriverStationDemo/DriverStationDemo.ino deleted file mode 100644 index 7bc0e7a..0000000 --- a/examples/__library_impl/DriverStationDemo/DriverStationDemo.ino +++ /dev/null @@ -1,18 +0,0 @@ -#include -#include -#include - -static probot::robot::StateService g_state; -static probot::io::GamepadService g_gamepad; -static probot::platform::esp32::DriverStation g_ds(g_state, g_gamepad); - -PROBOT_SET_DRIVER_STATION_PASSWORD("ProBot1234"); - -// TestDriverStationDemo - -void robotInit() {} -void robotEnd() {} -void teleopInit() {} -void teleopLoop() { delay(100); } -void autonomousInit() {} -void autonomousLoop() { delay(1000); } \ No newline at end of file diff --git a/examples/__library_impl/LoopPeriodStress/LoopPeriodStress.ino b/examples/__library_impl/LoopPeriodStress/LoopPeriodStress.ino deleted file mode 100644 index f188b8b..0000000 --- a/examples/__library_impl/LoopPeriodStress/LoopPeriodStress.ino +++ /dev/null @@ -1,10 +0,0 @@ -#include - -// TestLoopPeriodStress - -void robotInit() {} -void robotEnd() {} -void teleopInit() {} -void teleopLoop() { delay(50); } -void autonomousInit() {} -void autonomousLoop() { delay(1000); } \ No newline at end of file diff --git a/examples/__library_impl/RGBClosedLoop/RGBClosedLoop.ino b/examples/__library_impl/RGBClosedLoop/RGBClosedLoop.ino deleted file mode 100644 index 8a49a08..0000000 --- a/examples/__library_impl/RGBClosedLoop/RGBClosedLoop.ino +++ /dev/null @@ -1,10 +0,0 @@ -#include - -// TestRGBClosedLoop - -void robotInit() {} -void robotEnd() {} -void teleopInit() {} -void teleopLoop() { delay(500); } -void autonomousInit() {} -void autonomousLoop() { delay(1000); } \ No newline at end of file diff --git a/examples/__library_impl/TestSlider/TestSlider.ino b/examples/__library_impl/TestSlider/TestSlider.ino deleted file mode 100644 index b380ed7..0000000 --- a/examples/__library_impl/TestSlider/TestSlider.ino +++ /dev/null @@ -1,44 +0,0 @@ -#include -PROBOT_SET_DRIVER_STATION_PASSWORD("ProBot1234"); - -// TestSlider: demonstrate Slider controlling position of a single axis - -static probot::test::TestMotor mot; -static probot::test::TestEncoder enc; -static probot::control::PidConfig cfgP{ 0.0012f, 0.0f, 0.00002f, 0.0f, -1.0f, 1.0f }; -static probot::control::PID pid(cfgP); -static probot::control::ClosedLoopMotor* axis=nullptr; -static probot::mechanism::Slider* slider=nullptr; - -void robotInit(){ - control::setGlobalPeriodMs(20); - static probot::control::ClosedLoopMotor x(&enc, &pid, &mot, 1.0f, 1.0f); - axis = &x; - axis->setPidSlotConfig(1, cfgP); - axis->selectDefaultSlot(probot::control::ControlType::kPosition, 1); - static probot::test::TestPlant plant(&mot, &enc); - control::attach(axis); - control::attach(&plant); - - static probot::mechanism::Slider s(axis); - slider = &s; - slider->setLengthToTicks(100.0f); // 1 unit -> 100 ticks - control::attach(slider); -} - -void robotEnd() {} -void teleopInit(){ Serial.println("[SLID] teleopInit"); } - -void teleopLoop(){ - static uint32_t last=0; uint32_t now=joystick::get_ms(); - if (now - last >= 2000){ - last = now; - static bool toggle=false; toggle=!toggle; - slider->setTargetLength(toggle ? 5.0f : 0.0f); // units - Serial.printf("[SLID] target=%.1f units\n", slider->getTargetLength()); - } - delay(20); -} - -void autonomousInit(){} -void autonomousLoop(){ delay(1000); } diff --git a/examples/__library_impl/TestTankDrive/TestTankDrive.ino b/examples/__library_impl/TestTankDrive/TestTankDrive.ino deleted file mode 100644 index d63499c..0000000 --- a/examples/__library_impl/TestTankDrive/TestTankDrive.ino +++ /dev/null @@ -1,59 +0,0 @@ -#include -PROBOT_SET_DRIVER_STATION_PASSWORD("ProBot1234"); - -// TestTankDrive: demonstrate BasicTankDrive chassis and Slider with sims - -static probot::test::TestMotor motL, motR; -static probot::test::TestEncoder encL, encR; -static probot::control::PidConfig cfgV{ 0.0009f, 0.0003f, 0.00002f, 0.0f, -1.0f, 1.0f }; -static probot::control::PidConfig cfgP{ 0.0008f, 0.0f, 0.00001f, 0.0f, -1.0f, 1.0f }; -static probot::control::PID pidL(cfgV), pidR(cfgV); -static probot::control::ClosedLoopMotor *axisL=nullptr, *axisR=nullptr; -static probot::drive::BasicTankDrive* chassis=nullptr; - -void robotInit() { - control::setGlobalPeriodMs(20); - static probot::control::ClosedLoopMotor xL(&encL, &pidL, &motL, 1.0f, 1.0f); - static probot::control::ClosedLoopMotor xR(&encR, &pidR, &motR, 1.0f, 1.0f); - axisL = &xL; axisR = &xR; - axisL->setPidSlotConfig(0, cfgV); axisL->setPidSlotConfig(1, cfgP); - axisR->setPidSlotConfig(0, cfgV); axisR->setPidSlotConfig(1, cfgP); - axisL->selectDefaultSlot(probot::control::ControlType::kVelocity, 0); - axisR->selectDefaultSlot(probot::control::ControlType::kVelocity, 0); - - static probot::test::TestPlant pL(&motL, &encL); - static probot::test::TestPlant pR(&motR, &encR); - - control::attach(axisL); - control::attach(axisR); - control::attach(&pL); - control::attach(&pR); - - static probot::drive::BasicTankDrive ch(axisL, axisR); - chassis = &ch; - chassis->setWheelCircumference(20.0f); // arbitrary units - chassis->setTrackWidth(30.0f); -} - -void robotEnd() {} - -void teleopInit() { - Serial.println("[TANK] teleopInit: velocity drive"); -} - -void teleopLoop() { - // Alternate velocity and position commands - static uint32_t last=0; uint32_t now=joystick::get_ms(); - if (now - last >= 2000){ - last = now; - static int step=0; step = (step+1)%4; - if (step==0){ chassis->setVelocity(200.0f, 200.0f); Serial.println("[TANK] vel fwd"); } - else if (step==1){ chassis->setVelocity(-200.0f, -200.0f); Serial.println("[TANK] vel back"); } - else if (step==2){ chassis->driveDistance(10.0f); Serial.println("[TANK] drive +10"); } - else { chassis->turnDegrees(90.0f); Serial.println("[TANK] turn +90"); } - } - delay(20); -} - -void autonomousInit() { Serial.println("[TANK] auto: drive 10, turn 90"); chassis->driveDistance(10.0f); } -void autonomousLoop() { delay(1000); } diff --git a/examples/nfr/AdvancedMecanumDrive/AdvancedMecanumDrive.ino b/examples/nfr/AdvancedMecanumDrive/AdvancedMecanumDrive.ino deleted file mode 100644 index 5d44eff..0000000 --- a/examples/nfr/AdvancedMecanumDrive/AdvancedMecanumDrive.ino +++ /dev/null @@ -1,75 +0,0 @@ -#include -#include -#include -#include - -static probot::motor::NullMotor flHW, frHW, rlHW, rrHW; - -class NullMotorController : public probot::control::IMotorController { -public: - explicit NullMotorController(probot::motor::IMotorDriver& driver) : driver_(driver) {} - bool setPower(float power) override { return driver_.setPower(power); } - void setInverted(bool inv) override { driver_.setInverted(inv); } - bool getInverted() const override { return driver_.getInverted(); } - void setSetpoint(float, probot::controllers::ControlType, int) override {} - void setTimeoutMs(uint32_t) override {} - void setPidSlotConfig(int, const probot::control::PidConfig&) override {} - void selectDefaultSlot(probot::controllers::ControlType, int) override {} - int defaultSlot(probot::controllers::ControlType) const override { return 0; } - float lastSetpoint() const override { return 0.0f; } - float lastMeasurement() const override { return 0.0f; } - float lastOutput() const override { return 0.0f; } - probot::controllers::ControlType activeMode() const override { return probot::controllers::ControlType::kVelocity; } - bool isAtTarget(float) const override { return false; } - void setMotionProfile(probot::control::MotionProfileType type) override { profileType_ = type; } - probot::control::MotionProfileType motionProfile() const override { return profileType_; } - void setMotionProfileConfig(const probot::control::MotionProfileConfig& cfg) override { profileCfg_ = cfg; } - probot::control::MotionProfileConfig motionProfileConfig() const override { return profileCfg_; } - void update(uint32_t, uint32_t) override {} -private: - probot::motor::IMotorDriver& driver_; - probot::control::MotionProfileType profileType_{probot::control::MotionProfileType::kNone}; - probot::control::MotionProfileConfig profileCfg_{}; -}; - -static NullMotorController fl(flHW), fr(frHW), rl(rlHW), rr(rrHW); -static probot::chassis::NfrAdvancedMecanumDrive::Config config; -static probot::chassis::NfrAdvancedMecanumDrive chassis(&fl, &fr, &rl, &rr, config); -static probot::sensors::imu::Mpu6050 imu; - -static probot::control::kinematics::WheelPositions4 wheelPositions{}; - -void robotInit(){ - Serial.println("[AdvancedMecanumDrive] robotInit"); - chassis.setImu(&imu); - chassis.setFeedforwardGains(0.05f, 0.9f, 0.1f); - chassis.setWheelMotionProfile(probot::control::MotionProfileType::kTrapezoid, - {0.6f, 1.8f, 0.0f}); - chassis.useMotorControllerVelocityLoop(true); - chassis.resetPose(probot::control::Pose2d(), 0.0f, wheelPositions); -} - -void teleopInit(){ Serial.println("[AdvancedMecanumDrive] teleopInit"); } - -void teleopLoop(){ - static uint32_t lastMs = 0; - uint32_t now = millis(); - float dt = (now - lastMs) * 0.001f; - if (dt <= 0.0f) dt = 0.02f; - lastMs = now; - - // Simulated wheel motion for demo (forward motion) - float delta = 0.3f * dt; - wheelPositions.frontLeft += delta; - wheelPositions.frontRight += delta; - wheelPositions.rearLeft += delta; - wheelPositions.rearRight += delta; - - chassis.setTargetSpeeds(probot::control::ChassisSpeeds(0.3f, 0.0f, 0.0f)); - chassis.update(now * 0.001f, wheelPositions); - delay(20); -} - -void autonomousInit(){ Serial.println("[AdvancedMecanumDrive] autonomousInit"); } -void autonomousLoop(){ delay(20); } -void robotEnd(){ Serial.println("[AdvancedMecanumDrive] robotEnd"); } diff --git a/examples/nfr/AdvancedTankDrive/AdvancedTankDrive.ino b/examples/nfr/AdvancedTankDrive/AdvancedTankDrive.ino deleted file mode 100644 index 44ef37f..0000000 --- a/examples/nfr/AdvancedTankDrive/AdvancedTankDrive.ino +++ /dev/null @@ -1,87 +0,0 @@ -#include -#include -#include -#include -#include -#include - -// Example demonstrating the NFRAdvancedTankDrive structure with simulated hardware. - -static probot::motor::NullMotor leftHW; -static probot::motor::NullMotor rightHW; -static probot::control::PID pidLeft({0.4f,0.0f,0.0f,-1.0f,1.0f}); -static probot::control::PID pidRight({0.4f,0.0f,0.0f,-1.0f,1.0f}); - -// Null controllers stand in for real motor controllers – swap with real ones on hardware. -class NullMotorController : public probot::control::IMotorController { -public: - explicit NullMotorController(probot::motor::IMotorDriver& driver) : driver_(driver) {} - bool setPower(float power) override { return driver_.setPower(power); } - void setInverted(bool inv) override { driver_.setInverted(inv); } - bool getInverted() const override { return driver_.getInverted(); } - - void setSetpoint(float value, probot::control::ControlType mode, int slot = -1) override {} - void setTimeoutMs(uint32_t) override {} - void setPidSlotConfig(int, const probot::control::PidConfig&) override {} - void selectDefaultSlot(probot::control::ControlType, int) override {} - int defaultSlot(probot::control::ControlType) const override { return 0; } - float lastSetpoint() const override { return 0.0f; } - float lastMeasurement() const override { return 0.0f; } - float lastOutput() const override { return 0.0f; } - probot::control::ControlType activeMode() const override { return probot::control::ControlType::kVelocity; } - bool isAtTarget(float) const override { return false; } - void setMotionProfile(probot::control::MotionProfileType type) override { profileType_ = type; } - probot::control::MotionProfileType motionProfile() const override { return profileType_; } - void setMotionProfileConfig(const probot::control::MotionProfileConfig& cfg) override { profileCfg_ = cfg; } - probot::control::MotionProfileConfig motionProfileConfig() const override { return profileCfg_; } - void update(uint32_t, uint32_t) override {} -private: - probot::motor::IMotorDriver& driver_; - probot::control::MotionProfileType profileType_{probot::control::MotionProfileType::kNone}; - probot::control::MotionProfileConfig profileCfg_{}; -}; - -static NullMotorController leftController(leftHW); -static NullMotorController rightController(rightHW); - -static probot::chassis::NfrAdvancedTankDrive::Config config; -static probot::chassis::NfrAdvancedTankDrive chassis(&leftController, &rightController, config); -static probot::sensors::imu::Mpu6050 imu; - -// Simulated encoder positions -static float leftPosition = 0.0f; -static float rightPosition = 0.0f; - -void robotInit(){ - Serial.println("[AdvancedTankDrive] robotInit"); - chassis.setImu(&imu); - chassis.setFeedforwardGains(0.1f, 1.0f, 0.1f); - chassis.setWheelMotionProfile(probot::control::MotionProfileType::kTrapezoid, - {0.8f, 2.0f, 0.0f}); - chassis.useMotorControllerVelocityLoop(true); - chassis.setVelocityPidConfig({0.5f,0.0f,0.0f,0.0f,-1.0f,1.0f}); - chassis.setRamseteParams(2.0f, 0.7f); - chassis.resetPose(probot::control::Pose2d(), leftPosition, rightPosition); -} - -void teleopInit(){ Serial.println("[AdvancedTankDrive] teleopInit"); } - -void teleopLoop(){ - static uint32_t last = 0; - uint32_t now = millis(); - float dt = (now - last) * 0.001f; - if (dt <= 0.0f) dt = 0.02f; - last = now; - - float desiredV = 0.5f; - leftPosition += desiredV * dt; - rightPosition += desiredV * dt; - - chassis.setTargetSpeeds(probot::control::ChassisSpeeds(desiredV, 0.0f, 0.0f)); - chassis.update(now * 0.001f, leftPosition, rightPosition); - delay(20); -} - -void autonomousInit(){ Serial.println("[AdvancedTankDrive] autonomousInit"); } -void autonomousLoop(){ delay(20); } -void robotEnd(){ Serial.println("[AdvancedTankDrive] robotEnd"); } From 11ef9de77791850bf68119b065b41407fa8bca39 Mon Sep 17 00:00:00 2001 From: tunapro Date: Sun, 19 Oct 2025 07:33:44 +0300 Subject: [PATCH 24/26] Add LoggingDemo example to exercise new logging stack --- examples/LoggingDemo/LoggingDemo.ino | 111 ++++++++++++++++++++++++++ src/platform/esp32s3/web/index_html.h | 2 +- 2 files changed, 112 insertions(+), 1 deletion(-) create mode 100644 examples/LoggingDemo/LoggingDemo.ino diff --git a/examples/LoggingDemo/LoggingDemo.ino b/examples/LoggingDemo/LoggingDemo.ino new file mode 100644 index 0000000..99d0e2e --- /dev/null +++ b/examples/LoggingDemo/LoggingDemo.ino @@ -0,0 +1,111 @@ +/** + * 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/src/platform/esp32s3/web/index_html.h b/src/platform/esp32s3/web/index_html.h index 95f5f68..5be22bc 100644 --- a/src/platform/esp32s3/web/index_html.h +++ b/src/platform/esp32s3/web/index_html.h @@ -5,7 +5,7 @@ #include #endif -const char MAIN_page[] PROGMEM = R"===== +const char MAIN_page[] PROGMEM = R"=====( From 12f4e95bd974af0395b3d13f49260769ce7cab1d Mon Sep 17 00:00:00 2001 From: tunapro Date: Sun, 19 Oct 2025 14:40:10 +0300 Subject: [PATCH 25/26] Add cross-platform build metadata and ESP-IDF support --- CMakeLists.txt | 28 ++++++++ Makefile | 8 +++ README.md | 20 ++++++ VERSION | 1 + idf_component.yml | 8 +++ library.json | 30 +++++++++ tools/sync_version.py | 152 ++++++++++++++++++++++++++++++++++++++++++ 7 files changed, 247 insertions(+) create mode 100644 CMakeLists.txt create mode 100644 VERSION create mode 100644 idf_component.yml create mode 100644 library.json create mode 100755 tools/sync_version.py diff --git a/CMakeLists.txt b/CMakeLists.txt new file mode 100644 index 0000000..1d5d348 --- /dev/null +++ b/CMakeLists.txt @@ -0,0 +1,28 @@ +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 +) + +target_compile_definitions(${COMPONENT_TARGET} + PUBLIC + ARDUINO=10820 + ESP32 + ESP32S3 +) diff --git a/Makefile b/Makefile index 75d25d0..9430c0b 100644 --- a/Makefile +++ b/Makefile @@ -5,6 +5,10 @@ FQBN ?= esp32:esp32:esp32s3 PORT ?= /dev/ttyACM0 BAUD ?= 115200 ARDUINO_CLI ?= arduino-cli +PYTHON ?= python3 + +VERSION_FILE := $(CURDIR)/VERSION +VERSION_SYNC_SCRIPT := $(CURDIR)/tools/sync_version.py # Examples EXAMPLES_DIR := $(CURDIR)/examples @@ -57,6 +61,7 @@ build-all: _build_single: @echo "==> Building $(EXAMPLE)" + $(PYTHON) $(VERSION_SYNC_SCRIPT) $(ARDUINO_CLI) compile --fqbn $(FQBN) --warnings all \ --library $(CURDIR) \ --build-path $(BUILD_DIR_BASE)/$(EXAMPLE) \ @@ -81,6 +86,9 @@ boards: libs: arduino-cli lib install "Adafruit NeoPixel" +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) diff --git a/README.md b/README.md index 58caac8..ba07ee0 100644 --- a/README.md +++ b/README.md @@ -40,6 +40,16 @@ 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. +- **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. + +Tüm platformlarda sürüm numarası `VERSION` dosyasından yönetilir; `make version-sync` çağrısı metadata dosyalarını günceller. + +--- + ## Ne içeriyor? Kütüphane şunları sağlar: @@ -138,6 +148,16 @@ 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`. +- **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. + +`make version-sync` keeps all manifests aligned with the single `VERSION` file. + +--- + ## What's inside? The library provides: diff --git a/VERSION b/VERSION new file mode 100644 index 0000000..d917d3e --- /dev/null +++ b/VERSION @@ -0,0 +1 @@ +0.1.2 diff --git a/idf_component.yml b/idf_component.yml new file mode 100644 index 0000000..e708c36 --- /dev/null +++ b/idf_component.yml @@ -0,0 +1,8 @@ +version: 0.1.2 +description: ESP32-S3 robotics control library +url: https://github.com/nfrproducts/probot-lib +dependencies: + idf: + version: ">=5.0" + espressif/arduino-esp32: + version: ">=3.0.0" diff --git a/library.json b/library.json new file mode 100644 index 0000000..79a50ac --- /dev/null +++ b/library.json @@ -0,0 +1,30 @@ +{ + "build": { + "flags": [ + "-DESP32S3", + "-DARDUINO_USB_MODE=1" + ] + }, + "dependencies": [ + { + "name": "Adafruit NeoPixel", + "version": ">=1.12.0" + } + ], + "description": "ESP32-S3 robotics control library", + "frameworks": "arduino", + "keywords": [ + "robotics", + "pid", + "motion-control" + ], + "name": "Probot Lib", + "platforms": [ + "espressif32" + ], + "repository": { + "type": "git", + "url": "https://github.com/nfrproducts/probot-lib" + }, + "version": "0.1.2" +} diff --git a/tools/sync_version.py b/tools/sync_version.py new file mode 100755 index 0000000..4a14e23 --- /dev/null +++ b/tools/sync_version.py @@ -0,0 +1,152 @@ +#!/usr/bin/env python3 +"""Synchronise project version across metadata files. + +Reads the semver string from VERSION and ensures both library.properties +and library.json expose the same value. The script is idempotent and only +touches the files when an update is required. +""" + +from __future__ import annotations + +import json +import sys +from pathlib import Path + + +class VersionSyncError(RuntimeError): + pass + + +def read_version(version_path: Path) -> str: + try: + version = version_path.read_text(encoding="utf-8").strip() + except OSError as exc: # pragma: no cover - catastrophic failure + raise VersionSyncError(f"Failed to read {version_path}") from exc + + if not version: + raise VersionSyncError(f"VERSION file {version_path} is empty") + return version + + +def update_library_properties(path: Path, version: str) -> bool: + if not path.exists(): + raise VersionSyncError(f"Missing {path} required for Arduino metadata") + + text = path.read_text(encoding="utf-8").splitlines() + updated = False + for idx, line in enumerate(text): + if line.startswith("version="): + if line != f"version={version}": + text[idx] = f"version={version}" + updated = True + break + else: + text.append(f"version={version}") + updated = True + + if updated: + path.write_text("\n".join(text) + "\n", encoding="utf-8") + return updated + + +def default_library_json() -> dict: + return { + "name": "Probot Lib", + "version": "0.0.0", + "description": "ESP32-S3 robotics control library", + "keywords": ["robotics", "pid", "motion-control"], + "repository": { + "type": "git", + "url": "https://github.com/nfrproducts/probot-lib" + }, + "frameworks": "arduino", + "platforms": ["espressif32"], + "build": { + "flags": ["-DESP32S3", "-DARDUINO_USB_MODE=1"] + }, + "dependencies": [ + { + "name": "Adafruit NeoPixel", + "version": ">=1.12.0" + } + ] + } + + +def update_library_json(path: Path, version: str) -> bool: + if path.exists(): + try: + data = json.loads(path.read_text(encoding="utf-8")) + except json.JSONDecodeError as exc: + raise VersionSyncError(f"Invalid JSON in {path}") from exc + else: + data = default_library_json() + + if data.get("version") == version: + return False + + data["version"] = version + path.write_text(json.dumps(data, indent=2, sort_keys=True) + "\n", encoding="utf-8") + return True + + +def update_idf_component(path: Path, version: str) -> bool: + if not path.exists(): + template = [ + f"version: {version}", + "description: ESP32-S3 robotics control library", + "url: https://github.com/nfrproducts/probot-lib", + "dependencies:", + " idf:", + " version: \">=5.0\"", + " espressif/arduino-esp32:", + " version: \">=3.0.0\"", + ] + path.write_text("\n".join(template) + "\n", encoding="utf-8") + return True + + lines = path.read_text(encoding="utf-8").splitlines() + updated = False + for idx, line in enumerate(lines): + stripped = line.lstrip() + if stripped.startswith("version:"): + indent = line[: len(line) - len(stripped)] + replacement = f"{indent}version: {version}" + if line != replacement: + lines[idx] = replacement + updated = True + break + else: + lines.insert(0, f"version: {version}") + updated = True + + if updated: + path.write_text("\n".join(lines) + "\n", encoding="utf-8") + return updated + + +def main() -> int: + root = Path(__file__).resolve().parent.parent + version_path = root / "VERSION" + lib_props_path = root / "library.properties" + lib_json_path = root / "library.json" + + version = read_version(version_path) + + props_changed = update_library_properties(lib_props_path, version) + json_changed = update_library_json(lib_json_path, version) + + idf_yaml_path = root / "idf_component.yml" + idf_changed = update_idf_component(idf_yaml_path, version) + + if props_changed or json_changed or idf_changed: + sys.stdout.write(f"Version metadata synced to {version}\n") + return 0 + + +if __name__ == "__main__": + try: + raise SystemExit(main()) + except VersionSyncError as exc: + sys.stderr.write(f"error: {exc}\n") + raise SystemExit(1) From bfa61a66b3465963536bfa2b7eb328e7253938a6 Mon Sep 17 00:00:00 2001 From: tunapro Date: Mon, 20 Oct 2025 12:44:33 +0300 Subject: [PATCH 26/26] chore(release): bump metadata for 0.1.4 --- VERSION | 2 +- idf_component.yml | 2 +- library.json | 2 +- library.properties | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/VERSION b/VERSION index d917d3e..845639e 100644 --- a/VERSION +++ b/VERSION @@ -1 +1 @@ -0.1.2 +0.1.4 diff --git a/idf_component.yml b/idf_component.yml index e708c36..d0bcdef 100644 --- a/idf_component.yml +++ b/idf_component.yml @@ -1,4 +1,4 @@ -version: 0.1.2 +version: 0.1.4 description: ESP32-S3 robotics control library url: https://github.com/nfrproducts/probot-lib dependencies: diff --git a/library.json b/library.json index 79a50ac..8649faf 100644 --- a/library.json +++ b/library.json @@ -26,5 +26,5 @@ "type": "git", "url": "https://github.com/nfrproducts/probot-lib" }, - "version": "0.1.2" + "version": "0.1.4" } diff --git a/library.properties b/library.properties index a946ea2..39712d3 100644 --- a/library.properties +++ b/library.properties @@ -1,5 +1,5 @@ name=probot -version=0.1.2 +version=0.1.4 author=Tuna Gül maintainer=Tuna Gül sentence=ProBot Library for Robotics Competitions.