diff --git a/.github/workflows/hardware-test.yml b/.github/workflows/hardware-test.yml new file mode 100644 index 0000000..e8a07c1 --- /dev/null +++ b/.github/workflows/hardware-test.yml @@ -0,0 +1,53 @@ +name: Hardware Integration Tests + +on: + push: + paths: + - 'XRPLib/**' + - 'tests/hardware/**' + pull_request: + paths: + - 'XRPLib/**' + - 'tests/hardware/**' + workflow_dispatch: # Allow manual trigger + +jobs: + hardware-tests: + name: Run XRP Hardware Tests + runs-on: self-hosted-xrp-teststand # Self-hosted runner with XRP test stand + timeout-minutes: 10 + + steps: + - name: Checkout code + uses: actions/checkout@v4 + + - name: Set up Python + uses: actions/setup-python@v5 + with: + python-version: '3.11' + + - name: Install mpremote + run: pip install mpremote + + - name: Run hardware tests + run: python scripts/ci_hardware_test.py + + unit-tests: + name: Run Unit Tests + runs-on: ubuntu-latest + timeout-minutes: 5 + + steps: + - name: Checkout code + uses: actions/checkout@v4 + + - name: Set up Python + uses: actions/setup-python@v5 + with: + python-version: '3.11' + + - name: Install pytest + run: pip install pytest + + - name: Run unit tests + run: pytest tests/unit/ -v diff --git a/CODE_REVIEW.md b/CODE_REVIEW.md new file mode 100644 index 0000000..ed1d746 --- /dev/null +++ b/CODE_REVIEW.md @@ -0,0 +1,252 @@ +# XRP MicroPython Library — Code Review + +## Bugs + +### 1. `return Exception` instead of `raise Exception` +**File:** `XRPLib/encoded_motor.py:62` + +```python +return Exception("Invalid motor index") # returns the exception object silently +``` + +Should be `raise Exception(...)`. Currently an invalid index silently returns an Exception object as if it were a motor, which will cause a confusing `AttributeError` later when the caller tries to use it. + +--- + +### 2. IMU `gyro_rate()` reads wrong register bits +**File:** `XRPLib/imu.py:484` + +```python +index = list(LSM_ODR.values()).index(self.reg_ctrl1_xl_bits.ODR_G) +``` + +This reads `ODR_G` from `reg_ctrl1_xl_bits` (the **accelerometer** control register) instead of from `reg_ctrl2_g_bits` (the **gyroscope** control register). Should be: + +```python +index = list(LSM_ODR.values()).index(self.reg_ctrl2_g_bits.ODR_G) +``` + +--- + +### 3. IMU `timer_frequency` not initialized in `__init__` +**File:** `XRPLib/imu.py` + +`self.timer_frequency` is only set inside `gyro_rate()` (line 492), but the timer is started in `reset()` -> `_default_config()` -> `gyro_rate('208Hz')`. If `_start_timer()` is ever called before `gyro_rate()` completes (e.g. in a subclass override or future refactor), you get an `AttributeError`. It should be initialized in `__init__` or `_reset_member_variables()`. + +--- + +### 4. `Timeout` and IMU use raw `ticks_ms` arithmetic instead of `ticks_diff` +**Files:** `XRPLib/timeout.py:23`, `XRPLib/imu.py:184`, `XRPLib/imu.py:514` + +```python +# timeout.py:23 +return time.ticks_ms() - self.start_time > self.timeout + +# imu.py:184 +while time.ticks_ms() < (t0 + wait_timeout_ms): + +# imu.py:514 +while time.ticks_ms() < start_time + calibration_time*1000: +``` + +`ticks_ms()` wraps around (it's a 30-bit counter on MicroPython). All of these should use `time.ticks_diff(time.ticks_ms(), start_time)` to handle wraparound correctly. These will malfunction if `ticks_ms` wraps during operation (~12.4 days on RP2040). + +--- + +### 5. `_getregs` allocates on the heap inside timer callback +**File:** `XRPLib/imu.py:108-111` + +```python +def _getregs(self, reg, num_bytes): + rx_buf = bytearray(num_bytes) # heap allocation every call +``` + +`_update_imu_readings()` is called from a timer callback and calls `get_gyro_rates()` -> `_getregs()`, which allocates a new `bytearray(6)` every call (~208 times/second). In MicroPython timer callbacks, heap allocation can trigger GC and cause crashes or unpredictable timing. Should use a pre-allocated buffer. + +--- + +### 6. I2C operations in timer callback context +**File:** `XRPLib/imu.py:548-553` + +The `_update_imu_readings` callback does I2C reads (`readfrom_mem_into`). I2C is a slow bus protocol. MicroPython's soft timers (Timer -1) do run in a thread-safe context (not hard IRQ), so this *works*, but it blocks other soft timer callbacks (like motor speed updates at 50 Hz) for the duration of the I2C transaction. Consider using `micropython.schedule()` to defer this work. + +--- + +## Concurrency / Race Conditions + +### 7. Shared mutable `irq_v` array without protection +**File:** `XRPLib/imu.py:82` + +`get_acc_rates()`, `get_gyro_rates()`, and `get_acc_gyro_rates()` all write to `self.irq_v` and return it. The timer callback also calls `get_gyro_rates()` which mutates `irq_v[1]`. If user code calls `get_acc_gyro_rates()` while the timer fires, the gyro values in the returned array could be partially overwritten. The returned list is a shared reference, not a copy. + +--- + +### 8. Rangefinder `_trigger_ping` does busy-wait in timer callback +**File:** `XRPLib/rangefinder.py:92-116` + +The timer callback calls `_trigger_ping()` which does a busy-wait `_delay_us(10)`. Timer callbacks with `Timer(-1)` are soft callbacks on RP2040, but the ~15us busy-wait still blocks other callbacks. If the platform treats virtual timers as hard IRQs, the busy loop could cause watchdog issues. + +--- + +### 9. Rangefinder floating-point division in hard IRQ +**File:** `XRPLib/rangefinder.py:134` + +```python +self.cms = (pulse_time / 2) / 29.1 +``` + +The echo handler runs as a pin IRQ (hard IRQ). Floating-point division can allocate on the heap in MicroPython. Consider using integer arithmetic instead: + +```python +self.cms = pulse_time * 100 // 5820 # equivalent to pulse_time / 2 / 29.1 +``` + +--- + +## Design Issues + +### 10. `defaults.py` eagerly initializes all hardware +**File:** `XRPLib/defaults.py:18-29` + +Importing `defaults` creates ALL hardware objects including all 4 motors, the IMU (with 1-second calibration!), the rangefinder, servos, and webserver. Most programs only need 2 motors + drivetrain. This wastes: +- 1 second on IMU calibration every boot +- 4 PIO state machines (only 4 available per PIO block) +- 4 virtual timers for motor speed control (motors 3 & 4 usually unused) +- Rangefinder timer running continuously even when not needed + +Consider lazy initialization or splitting into separate import targets. + +--- + +### 11. Motor PWM frequency of 50 Hz is very low +**Files:** `XRPLib/motor.py:17`, `XRPLib/motor.py:63-64` + +50 Hz PWM means the motor duty cycle only updates every 20ms and produces audible whine. Typical DC motor PWM is 1-20 kHz. 50 Hz is the standard for servo control, not DC motors. This likely causes jerky low-speed performance and audible noise. + +--- + +### 12. Encoder `get_position_counts` reads PIO FIFO 5 times (blocking) +**File:** `XRPLib/encoder.py:47-52` + +```python +counts = self.sm.get() +counts = self.sm.get() +counts = self.sm.get() +counts = self.sm.get() +counts = self.sm.get() +``` + +This is called from the 50 Hz motor update timer callback. Each `sm.get()` blocks until data is in the FIFO. The PIO RX FIFO is 4 deep, so 5 reads drains the buffer and gets the freshest value. However, this is a blocking operation in a timer callback, which could cause timing jitter for other callbacks. + +--- + +### 13. PID `min_output` creates oscillation around setpoint +**File:** `XRPLib/pid.py:94-98` + +```python +if output > 0: + output = max(self.min_output, output) +else: + output = min(-self.min_output, output) +``` + +The output can NEVER be between `-min_output` and `+min_output` (excluding zero). When the error is very small, the output jumps between `+min_output` and `-min_output`, causing visible oscillation around the setpoint. The system only stops via the `is_done()` tolerance check in the calling code (`straight()`, `turn()`), but the robot will visibly jerk back and forth before stopping. + +--- + +### 14. PID never outputs zero +Related to issue #13. Since `min_output` forces the output to always be at least `+/-min_output`, the PID can never output 0. The system only stops via the `is_done()` tolerance check in calling code. If someone uses PID standalone without checking `is_done()`, the motors never stop. + +--- + +### 15. No cleanup/deinitialization for Rangefinder instances +**File:** `XRPLib/rangefinder.py:89` + +`_instances` is a class-level list that's never cleaned up. If a Rangefinder is garbage collected, it stays in `_instances`, and the timer callback will try to call `_do_ping` on a dead object. There's no `deinit()` method to remove the instance or stop the timer. + +--- + +## Memory & Performance + +### 16. String concatenation in `_generateHTML` +**File:** `XRPLib/webserver.py:234-258` + +Building HTML via repeated `string +=` creates many intermediate string objects. On a memory-constrained microcontroller, this can fragment the heap and trigger GC during request handling. Consider using a list and `''.join()`: + +```python +parts = [_HTML1] +# ... append to parts ... +return ''.join(parts) +``` + +--- + +### 17. `_raw_to_mg` and `_raw_to_mdps` receive sliced bytearrays +**File:** `XRPLib/imu.py:137-141` + +```python +def _raw_to_mg(self, raw): + return self._int16((raw[1] << 8) | raw[0]) * LSM_MG_PER_LSB_2G * self._acc_scale_factor +``` + +Called with `raw_bytes[0:2]` which creates a new `bytearray` slice each time. In the timer callback path, this means 3 allocations per update (~208 Hz). Pass buffer and index instead of slicing. + +--- + +## Minor Issues + +### 18. Typo: `ZERO_EFFORT_BREAK` should be `BRAKE` +**File:** `XRPLib/encoded_motor.py:10` + +```python +ZERO_EFFORT_BREAK = True # typo: should be ZERO_EFFORT_BRAKE +``` + +--- + +### 19. `webserver.py` creates a module-level instance with side effects +**File:** `XRPLib/webserver.py:261` + +The `webserver = Webserver()` at module level runs `gc.threshold(50000)` on import. This side effect happens even if you only import the class for type checking or introspection. + +--- + +### 20. Reflectance `MAX_ADC_VALUE` off by one +**File:** `XRPLib/reflectance.py:29` + +```python +self.MAX_ADC_VALUE: int = 65536 +``` + +The max value from `read_u16()` is 65535, so the sensor can never return exactly 1.0 (max is `65535/65536 = 0.99998`). Should be `65535` if a true [0, 1] range is desired. + +--- + +### 21. `DualPWMMotor.set_effort` doesn't clamp input +**File:** `XRPLib/motor.py:66-80` + +Unlike `SinglePWMMotor` which clamps effort to [0, 1], `DualPWMMotor` passes `abs(effort)` directly to `duty_u16()`. An effort > 1.0 would produce PWM values > 65535, which may wrap or error. + +--- + +### 22. IMU `is_connected()` check is ignored +**File:** `XRPLib/imu.py:56-58` + +```python +if not self.is_connected(): + # TODO - do somehting intelligent here + pass +``` + +If the IMU isn't connected, the code proceeds to `reset()` which will fail with an I2C error. Should raise an exception or return a null/dummy IMU. + +--- + +## Suggestions for Improvement + +- **Add a `deinit()` pattern** to all hardware classes (rangefinder, motors, IMU) to cleanly stop timers and release pins. Critical for REPL-based development where students restart code frequently. +- **Consider `micropython.schedule()`** for the IMU timer callback to avoid doing I2C in interrupt context. +- **Pre-allocate all buffers** used in timer/IRQ callbacks (especially the 6-byte and 12-byte reads in IMU). +- **Make `defaults.py` lazy** — use properties or functions so unused hardware isn't initialized. +- **Increase motor PWM frequency** to at least 1 kHz for smoother motor operation. +- **Add bounds checking** in `DualPWMMotor.set_effort` to match `SinglePWMMotor`. diff --git a/TEST_PLAN.md b/TEST_PLAN.md new file mode 100644 index 0000000..f724d87 --- /dev/null +++ b/TEST_PLAN.md @@ -0,0 +1,341 @@ +# XRP MicroPython Library — Test Plan + +## Overview + +This test plan has three tiers: + +1. **Unit tests** — Run on a desktop (CPython + pytest) with mocked hardware. These test pure logic: PID math, timeout behavior, arcade drive scaling, encoder math, data conversions, etc. They run in seconds and should be part of every PR/commit check. + +2. **Hardware integration tests (manual)** — Run on an XRP board (MicroPython) with a human operator. The operator presses a button to start, places surfaces for reflectance tests, and visually verifies LEDs and servos. + +3. **Hardware integration tests (automated test stand)** — The same tests run unattended on a dedicated test board. A `/teststand_mode` flag file on the Pico switches tests to auto-start and use instrumentation sensors instead of human verification. Triggered automatically on code checkins via GitHub Actions. + +--- + +## Directory Structure + +``` +tests/ +├── mocks/ +│ ├── __init__.py +│ ├── machine.py # Mock machine module (Pin, ADC, PWM, Timer, I2C) +│ ├── rp2.py # Mock rp2 module (PIO, StateMachine) +│ └── neopixel.py # Mock NeoPixel +├── unit/ +│ ├── __init__.py +│ ├── conftest.py # Pytest fixtures and mock installation +│ ├── test_pid.py # PID controller logic +│ ├── test_timeout.py # Timeout class +│ ├── test_motor.py # Motor effort clamping and direction +│ ├── test_encoded_motor.py # EncodedMotor singleton and error handling +│ ├── test_encoder.py # Encoder math (resolution, position conversion) +│ ├── test_differential_drive.py # Arcade drive scaling, encoder-to-cm math +│ ├── test_imu_math.py # IMU data conversions (_int16, _raw_to_mg, etc.) +│ ├── test_reflectance.py # Reflectance normalization +│ ├── test_servo.py # Servo angle-to-duty conversion +│ ├── test_motor_group.py # MotorGroup aggregation logic +│ ├── test_board.py # Board button logic, power detection +│ ├── test_rangefinder.py # Rangefinder distance calculation +│ ├── test_webserver.py # HTML generation, button registration +│ └── test_gamepad.py # Gamepad data parsing +├── hardware/ +│ ├── teststand.py # Test stand detection and sensor helpers +│ ├── run_all_hw_tests.py # Master runner (JSON output for CI) +│ ├── test_hw_motors.py # Motor direction, speed, braking +│ ├── test_hw_encoders.py # Encoder counting accuracy +│ ├── test_hw_drivetrain.py # Straight/turn accuracy +│ ├── test_hw_rangefinder.py # Distance measurement accuracy +│ ├── test_hw_reflectance.py # Reflectance sensor readings +│ ├── test_hw_imu.py # IMU readings and calibration +│ ├── test_hw_servo.py # Servo movement +│ ├── test_hw_board.py # LED, button, power switch +│ └── test_hw_timing.py # Timer callback timing accuracy +scripts/ +│ └── ci_hardware_test.py # Host-side CI script (sync + run + parse) +.github/workflows/ +│ └── hardware-test.yml # GitHub Actions (unit + hardware tests) +``` + +--- + +## Tier 1: Unit Tests (Desktop, no hardware) + +### How to run + +```bash +cd XRP_MicroPython +pip install pytest +pytest tests/unit/ -v +``` + +### What is tested + +| Test file | What it covers | +|-----------|---------------| +| `test_pid.py` | Proportional/integral/derivative math, output clamping, min_output behavior, integral windup, rate limiting, tolerance/is_done, clear_history | +| `test_timeout.py` | Timeout expiration, None timeout (never expires), ticks_diff correctness | +| `test_motor.py` | SinglePWMMotor effort clamping [0,1], direction flipping, DualPWMMotor direction XOR, brake/coast behavior, effort > 1.0 handling | +| `test_encoded_motor.py` | Invalid index raises exception (current bug), singleton pattern, speed-to-counts conversion, position inversion for flipped motors | +| `test_encoder.py` | Resolution calculation (585), position-to-revolutions conversion, wraparound handling (2^31/2^32) | +| `test_differential_drive.py` | Arcade drive scaling math, encoder-position-to-cm conversion, heading correction signs, straight/turn effort application | +| `test_imu_math.py` | `_int16` conversion, `_raw_to_mg`/`_raw_to_mdps` scaling, scale factor updates, angle integration math | +| `test_reflectance.py` | ADC normalization to [0, 1], edge values (0, 65535) | +| `test_servo.py` | Angle-to-duty_ns conversion, boundary angles (0, 200), free() behavior | +| `test_motor_group.py` | Average position/speed across motors, add/remove, set_effort delegation | +| `test_board.py` | `are_motors_powered` threshold, `is_button_pressed` inversion | +| `test_rangefinder.py` | Pulse-width-to-cm conversion, timeout handling (MAX_VALUE), instance registration | +| `test_webserver.py` | HTML generation, button registration, arrow display toggle | +| `test_gamepad.py` | Packet parsing, value normalization, button press detection | + +--- + +## Tier 2: Hardware Integration Tests + +### Two modes of operation + +All hardware tests support two modes, controlled by the presence of a `/teststand_mode` file on the Pico's filesystem: + +| | Manual Mode | Test Stand Mode | +|---|---|---| +| **Start** | Press user button | Starts immediately | +| **LED verification** | Visual check by human | Phototransistor reads ADC | +| **Servo verification** | Visual check by human | Break-beam sensor detects arm position | +| **Reflectance surfaces** | Human places white/dark paper | Servo-actuated sliding plate | +| **RGB LED** | Visual check by human | TCS34725 RGB color sensor (Phase 4) | +| **Button test** | Human presses button | GPIO toggle via spare pin (optional) | + +### Manual mode + +#### Prerequisites + +- XRP board with batteries connected and power switch ON +- Motors plugged in, shafts free to spin +- Ultrasonic rangefinder pointed at a wall or flat surface at a known distance +- USB connection to upload and run tests +- White paper and dark surface available (for reflectance tests) + +#### How to run + +```bash +# Run a single test file +mpremote run tests/hardware/test_hw_motors.py + +# Run all tests (will pause for button presses) +mpremote run tests/hardware/run_all_hw_tests.py +``` + +### Test stand mode (automated) + +#### Prerequisites + +- Automated test board with XRP controller PCB, motors, sensors mounted (see Test Stand Design below) +- `/teststand_mode` file on Pico filesystem: `mpremote exec "f = open('/teststand_mode', 'w'); f.close()"` +- USB connection to CI host + +#### How to run + +```bash +# Run all tests automatically (no button presses, no human checks) +mpremote run tests/hardware/run_all_hw_tests.py + +# Or use the CI script which handles sync + run + parse +python scripts/ci_hardware_test.py +``` + +--- + +### Test procedures + +#### `test_hw_motors.py` — Motor Direction and Speed +**Setup:** Motor shafts free to spin (no load). + +| Test | Procedure | Pass criteria | Verification | +|------|-----------|---------------|-------------| +| Forward effort | `set_effort(0.5)` on both motors for 1s | Both encoder positions > 0 | Encoder (auto) | +| Reverse effort | `set_effort(-0.5)` on both motors for 1s | Both encoder positions < 0 | Encoder (auto) | +| Independent direction | Left forward, right reverse for 1s | Left > 0, right < 0 | Encoder (auto) | +| Brake | `set_effort(0.5)` then `brake()` | Position stable (< 0.1 rev drift) | Encoder (auto) | +| Coast | `set_effort(0.5)` then `coast()` | No crash | Auto | +| Speed control | `set_speed(60)`, wait 2s | Speed 50-70 RPM | Encoder (auto) | +| Zero effort | `set_effort(0)` | Position stable | Encoder (auto) | + +#### `test_hw_encoders.py` — Encoder Counting +**Setup:** Motor shafts free to spin. + +| Test | Procedure | Pass criteria | Verification | +|------|-----------|---------------|-------------| +| Count direction | Drive motor forward 1s | Counts > 0 | Encoder (auto) | +| Reverse counts | Drive motor backward 1s | Counts < 0 | Encoder (auto) | +| Reset | Drive, reset, read | Position ≈ 0 | Encoder (auto) | +| Resolution | Drive ~1 revolution | 500-700 counts (~585 expected) | Encoder (auto) | +| Stationary consistency | 10 rapid reads, motor stopped | Spread ≤ 2 counts | Encoder (auto) | + +#### `test_hw_drivetrain.py` — Drivetrain Accuracy +**Setup:** Motors free to spin. Manual mode: flat surface with clear space. + +| Test | Procedure | Pass criteria | Verification | +|------|-----------|---------------|-------------| +| Straight 30cm | `straight(30, max_effort=0.5)` | Encoder avg 25-35cm | Encoder (auto) | +| Reverse 30cm | `straight(-30, max_effort=0.5)` | Encoder avg -35 to -25cm | Encoder (auto) | +| Turn 90 CW | `turn(90, max_effort=0.5)` | IMU yaw 80-100° | IMU (auto) | +| Turn 90 CCW | `turn(-90, max_effort=0.5)` | IMU yaw -100 to -80° | IMU (auto) | +| Timeout | `straight(10000, timeout=2)` | Returns False in < 3s | Timer (auto) | +| Square | 4× straight(20) + turn(90) | Final heading 340-380° | IMU (auto) | + +#### `test_hw_rangefinder.py` — Distance Measurement +**Setup:** Flat surface at known distance. Test stand: fixed wall at ~20cm. + +| Test | Procedure | Pass criteria | Verification | +|------|-----------|---------------|-------------| +| First reading | `distance()` | Returns a number | Type check (auto) | +| Reasonable range | `distance()` | 2-400cm or MAX_VALUE | Range check (auto) | +| Stability | 10 readings, 100ms apart | Max deviation < 3cm | Variance (auto) | +| Non-blocking | 100 calls, measure time | < 200ms total | Timer (auto) | + +#### `test_hw_reflectance.py` — Reflectance Sensors +**Manual:** Human places white/dark surfaces and presses button. +**Test stand:** Servo-actuated sliding plate with white/black halves. + +| Test | Procedure | Pass criteria | Verification | +|------|-----------|---------------|-------------| +| Values in range | Read both sensors | 0 ≤ value ≤ 1 | Range check (auto) | +| White surface | Sensors over white | Both < 0.4 | ADC (auto) | +| Dark surface | Sensors over dark | Both > 0.6 | ADC (auto) | + +#### `test_hw_imu.py` — IMU Readings +**Setup:** Board flat and stationary. + +| Test | Procedure | Pass criteria | Verification | +|------|-----------|---------------|-------------| +| Connection | `is_connected()` | True | I2C (auto) | +| Gravity Z | Read accelerometer Z | 800-1200 mg | IMU (auto) | +| Gravity X/Y | Read accelerometer X, Y | |X|, |Y| < 200 mg | IMU (auto) | +| Gyro at rest | Read gyroscope | All axes < 100 mdps | IMU (auto) | +| Yaw drift | Reset yaw, wait 5s | Drift < 3° | IMU (auto) | +| Temperature | `temperature()` | 15-45°C | IMU (auto) | +| Batch read | `get_acc_gyro_rates()` | 2×3 array | Shape check (auto) | + +#### `test_hw_servo.py` — Servo Movement +**Manual:** Visual check of servo arm. +**Test stand:** Break-beam sensor detects arm position at 0° vs 180°. + +| Test | Procedure | Pass criteria | Verification | +|------|-----------|---------------|-------------| +| Angle sweep | Set 0°, 90°, 180°, 90° | No crash; arm moves | Manual: visual. Stand: break-beam state changes | +| Free | `set_angle(90)` then `free()` | Servo releases | Manual: move by hand. Stand: no-crash check | + +#### `test_hw_board.py` — Board Peripherals +**Manual:** Visual check for LEDs, human button press. +**Test stand:** Phototransistor for LED, GPIO toggle for button. + +| Test | Procedure | Pass criteria | Verification | +|------|-----------|---------------|-------------| +| LED on/off | `led_on()` / `led_off()` | LED changes state | Manual: visual. Stand: phototransistor ADC delta > 1000 | +| LED blink | `led_blink(5)` for 1s | ~5 Hz blink | Manual: visual. Stand: 6-14 ADC transitions | +| Button press | Press and release button | Detected correctly | Manual: human press. Stand: GPIO toggle | +| Power detect | Read `are_motors_powered()` | True (batteries connected) | ADC (auto) | +| RGB LED | Set red, green, blue | Colors display | Manual: visual. Stand: TCS34725 (Phase 4) | + +#### `test_hw_timing.py` — Timer Callback Accuracy + +| Test | Procedure | Pass criteria | Verification | +|------|-----------|---------------|-------------| +| Motor update rate | Count callbacks for 1s | 40-60 Hz (target: 50) | Callback counter (auto) | +| IMU update rate | Count callbacks for 1s | 150-260 Hz (target: 208) | Callback counter (auto) | +| All timers | Run all timers for 10s | No crash | Survival check (auto) | + +--- + +## Tier 3: Automated Test Stand Design + +### Physical Layout + +The XRP controller PCB is mounted directly on a flat test board (~20cm × 25cm) with all peripherals. No chassis needed — the robot never drives anywhere. + +``` +┌──────────────────────────────────────────────┐ +│ Test Board (~20cm x 25cm) │ +│ │ +│ ┌──────────────────┐ │ +│ │ XRP Controller │ mounted flat │ +│ │ PCB (Pico W) │ (has LED, NeoPixel, │ +│ │ │ IMU, button on-board) │ +│ └──────────────────┘ │ +│ │ +│ ┌────┐ ┌────┐ │ +│ │ M1 │ │ M2 │ motors bolted down, │ +│ └────┘ └────┘ shafts free (no wheels) │ +│ │ +│ Rangefinder ─────► Fixed wall panel at 20cm │ +│ │ +│ ┌───────────┐ │ +│ │Reflectance│◄── sliding plate │ +│ │ sensors │ (white/black halves) │ +│ └───────────┘ actuated by stand servo │ +│ │ +│ Servo ──► break-beam sensor │ +│ │ +│ LED ◄── phototransistor in light tube │ +│ NeoPixel ◄── RGB color sensor (I2C) │ +└──────────────────────────────────────────────┘ +``` + +### Instrumentation wiring (spare Motor 3/4 and Servo 3/4 ports) + +| Connection | From | To | Purpose | +|---|---|---|---| +| LED sensor | Phototransistor (TEPT5700) | MOTOR_3_ENCODER_A (ADC) | Detect LED on/off/blink | +| Servo sensor | Break-beam phototransistor | MOTOR_3_ENCODER_B (digital in) | Detect servo arm position | +| Reflectance slide | Small servo | SERVO_4 (PWM) | Move white/black plate under sensors | +| RGB sensor | TCS34725 (I2C, addr 0x29) | I2C_SDA_1 / I2C_SCL_1 | Detect NeoPixel colors | +| Button test | SERVO_3 (GPIO output) | BOARD_USER_BUTTON via 1kΩ | Optional: toggle button pin | + +### Build phases + +| Phase | What | Tests enabled | +|---|---|---| +| **1: Software only** | `teststand.py`, `run_all_hw_tests.py`, `ci_hardware_test.py`, GitHub Actions workflow. Tests auto-start, visual checks skipped. | 38 of 45 (motors, encoders, drivetrain, IMU, rangefinder, timing) | +| **2: Test board + fixtures** | Mount PCB/motors/sensors on board. Fixed wall for rangefinder. Servo-actuated sliding plate for reflectance. | +3 (reflectance white/dark, rangefinder known distance) | +| **3: LED + servo sensors** | Phototransistor over LED. Break-beam at servo arm. | +3 (LED on/off, LED blink, servo sweep) | +| **4: RGB color sensor** | TCS34725 over NeoPixel. | +1 (RGB LED colors) | + +### CI pipeline + +The GitHub Actions workflow (`.github/workflows/hardware-test.yml`) runs two jobs: + +1. **Unit tests** — `ubuntu-latest`, runs `pytest tests/unit/ -v` +2. **Hardware tests** — `self-hosted-xrp-teststand` runner, runs `python scripts/ci_hardware_test.py` + +The CI host script (`scripts/ci_hardware_test.py`): +1. Detects Pico via `mpremote connect list` +2. Syncs XRPLib source and test files to the Pico +3. Creates `/teststand_mode` flag file +4. Runs `tests/hardware/run_all_hw_tests.py` +5. Parses JSON results line (`__RESULTS_JSON__:{...}`) +6. Returns exit code 0 (all pass) or 1 (any failure) + +--- + +## Regression Checklist + +When making changes, run: + +1. All unit tests (`pytest tests/unit/ -v`) +2. If motor/encoder changes: `test_hw_motors.py`, `test_hw_encoders.py` +3. If drivetrain/PID changes: `test_hw_drivetrain.py` +4. If sensor changes: relevant `test_hw_*.py` +5. If timer/IRQ changes: `test_hw_timing.py` +6. Full hardware suite before any release (`run_all_hw_tests.py`) + +On the automated test stand, steps 2-6 run automatically on every push to `XRPLib/**` or `tests/hardware/**`. + +--- + +## Known Limitations + +- Unit tests mock all hardware; they cannot catch real timing issues, I2C failures, or PIO state machine bugs +- In manual mode, some tests require human observation (LED visual, servo movement) +- In test stand mode (Phase 1), LED/servo/RGB tests verify no-crash only; full sensor verification requires Phases 2-4 +- Drivetrain accuracy depends on motor load; test stand motors have no wheels, so distances are encoder-based only +- IMU yaw drift test assumes the board is stationary — vibration from motors on the same test board could affect results +- The `json` module on MicroPython may not be available on all firmware builds; `run_all_hw_tests.py` falls back to print-based output diff --git a/scripts/ci_hardware_test.py b/scripts/ci_hardware_test.py new file mode 100644 index 0000000..b7f663a --- /dev/null +++ b/scripts/ci_hardware_test.py @@ -0,0 +1,161 @@ +#!/usr/bin/env python3 +""" +CI host-side script for running hardware tests on an XRP test stand. + +This script runs on the CI host machine (not on the Pico). It: +1. Detects the Pico's serial port +2. Syncs the XRPLib code to the Pico +3. Creates the /teststand_mode flag file +4. Uploads and runs the hardware test suite +5. Parses results and returns appropriate exit code + +Prerequisites: + pip install mpremote + +Usage: + python scripts/ci_hardware_test.py +""" +import subprocess +import sys +import json +import re +import os + + +def run_cmd(args, check=True, capture=True): + """Run a command and return its output.""" + print(f" > {' '.join(args)}") + result = subprocess.run( + args, + capture_output=capture, + text=True, + timeout=300, # 5 minute timeout + ) + if check and result.returncode != 0: + print(f" STDERR: {result.stderr}") + raise RuntimeError(f"Command failed: {' '.join(args)}") + return result + + +def detect_pico(): + """Verify mpremote can see a connected Pico.""" + result = run_cmd(["mpremote", "connect", "list"]) + if result.stdout.strip(): + print(f" Detected devices:\n{result.stdout}") + return True + else: + print(" No Pico detected!") + return False + + +def sync_xrplib(): + """Copy XRPLib source files to the Pico's lib directory.""" + print("\nSyncing XRPLib to Pico...") + # Create lib/XRPLib directory on Pico + run_cmd(["mpremote", "mkdir", ":lib"], check=False) + run_cmd(["mpremote", "mkdir", ":lib/XRPLib"], check=False) + + # Copy all .py files from XRPLib/ + xrplib_dir = os.path.join(os.path.dirname(__file__), "..", "XRPLib") + for filename in os.listdir(xrplib_dir): + if filename.endswith(".py"): + src = os.path.join(xrplib_dir, filename) + dst = f":lib/XRPLib/{filename}" + run_cmd(["mpremote", "cp", src, dst]) + print(" XRPLib synced.") + + +def sync_test_files(): + """Copy hardware test files to the Pico.""" + print("\nSyncing test files to Pico...") + run_cmd(["mpremote", "mkdir", ":tests"], check=False) + run_cmd(["mpremote", "mkdir", ":tests/hardware"], check=False) + + test_dir = os.path.join(os.path.dirname(__file__), "..", "tests", "hardware") + for filename in os.listdir(test_dir): + if filename.endswith(".py"): + src = os.path.join(test_dir, filename) + dst = f":tests/hardware/{filename}" + run_cmd(["mpremote", "cp", src, dst]) + print(" Test files synced.") + + +def ensure_teststand_mode(): + """Create the /teststand_mode flag file on the Pico.""" + print("\nSetting teststand mode...") + run_cmd(["mpremote", "exec", "f = open('/teststand_mode', 'w'); f.close()"]) + print(" Teststand mode enabled.") + + +def run_tests(): + """Run the hardware test suite and capture output.""" + print("\nRunning hardware tests...") + print("-" * 50) + + result = run_cmd( + ["mpremote", "run", "tests/hardware/run_all_hw_tests.py"], + check=False, + ) + + print(result.stdout) + if result.stderr: + print(f"STDERR: {result.stderr}") + + return result + + +def parse_results(output): + """Parse the JSON results line from test output.""" + for line in output.split("\n"): + if line.startswith("__RESULTS_JSON__:"): + json_str = line[len("__RESULTS_JSON__:"):] + return json.loads(json_str) + return None + + +def main(): + print("XRP Hardware Test CI Runner") + print("=" * 50) + + # Step 1: Detect Pico + print("\nDetecting Pico...") + if not detect_pico(): + print("\nFAIL: No Pico W detected. Check USB connection.") + sys.exit(1) + + # Step 2: Sync code + sync_xrplib() + sync_test_files() + + # Step 3: Enable teststand mode + ensure_teststand_mode() + + # Step 4: Run tests + result = run_tests() + + # Step 5: Parse and report + print("\n" + "=" * 50) + results = parse_results(result.stdout) + + if results is None: + print("FAIL: Could not parse test results from output.") + sys.exit(1) + + total = results["total_passed"] + results["total_failed"] + print(f"Final: {results['total_passed']}/{total} tests passed") + + if results["total_failed"] > 0: + print(f"\n{results['total_failed']} test(s) FAILED:") + for mod in results["modules"]: + if mod["failed"] > 0 or mod["error"]: + print(f" - {mod['name']}: {mod['failed']} failed") + if mod["error"]: + print(f" Error: {mod['error']}") + sys.exit(1) + else: + print("\nAll tests PASSED!") + sys.exit(0) + + +if __name__ == "__main__": + main() diff --git a/tests/__init__.py b/tests/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/tests/hardware/__init__.py b/tests/hardware/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/tests/hardware/run_all_hw_tests.py b/tests/hardware/run_all_hw_tests.py new file mode 100644 index 0000000..24e4276 --- /dev/null +++ b/tests/hardware/run_all_hw_tests.py @@ -0,0 +1,106 @@ +""" +Master test runner for all hardware integration tests. +Runs each test module sequentially and outputs a JSON summary. + +Usage: + mpremote run tests/hardware/run_all_hw_tests.py + +In teststand mode (file /teststand_mode exists on Pico), all tests +run without manual intervention. +""" +import sys +import time +import json + +# Test modules to run, in order +TEST_MODULES = [ + ("Board", "test_hw_board"), + ("Motors", "test_hw_motors"), + ("Encoders", "test_hw_encoders"), + ("Drivetrain", "test_hw_drivetrain"), + ("Rangefinder", "test_hw_rangefinder"), + ("Reflectance", "test_hw_reflectance"), + ("IMU", "test_hw_imu"), + ("Servo", "test_hw_servo"), + ("Timing", "test_hw_timing"), +] + +results = { + "total_passed": 0, + "total_failed": 0, + "modules": [], +} + + +def run_module(name, module_name): + """ + Run a test module by importing it. Each module prints its own + PASS/FAIL lines and sets module-level `passed` and `failed` counters. + """ + print() + print(f"{'='*50}") + print(f"Running: {name}") + print(f"{'='*50}") + + module_result = { + "name": name, + "module": module_name, + "passed": 0, + "failed": 0, + "error": None, + } + + try: + # Each test module runs its tests on import (top-level code) + mod = __import__(module_name) + module_result["passed"] = getattr(mod, "passed", 0) + module_result["failed"] = getattr(mod, "failed", 0) + except Exception as e: + module_result["error"] = str(e) + module_result["failed"] = 1 + print(f" ERROR: {e}") + + results["total_passed"] += module_result["passed"] + results["total_failed"] += module_result["failed"] + results["modules"].append(module_result) + + return module_result["failed"] == 0 and module_result["error"] is None + + +# Check teststand mode +try: + from teststand import is_teststand + mode = "TESTSTAND" if is_teststand() else "MANUAL" +except ImportError: + mode = "MANUAL" + +print(f"XRP Hardware Test Runner — Mode: {mode}") +print(f"Started at: {time.time()}") + +all_passed = True +for name, module_name in TEST_MODULES: + if not run_module(name, module_name): + all_passed = False + +# Print summary +print() +print("=" * 50) +print("SUMMARY") +print("=" * 50) +for mod in results["modules"]: + status = "PASS" if mod["failed"] == 0 and mod["error"] is None else "FAIL" + detail = f'{mod["passed"]} passed, {mod["failed"]} failed' + if mod["error"]: + detail += f' (ERROR: {mod["error"]})' + print(f" [{status}] {mod['name']}: {detail}") + +print() +print(f"Total: {results['total_passed']} passed, {results['total_failed']} failed") + +# Output machine-readable JSON on a tagged line for CI parsing +print() +print(f"__RESULTS_JSON__:{json.dumps(results)}") + +# Exit with appropriate code +if not all_passed: + sys.exit(1) diff --git a/tests/hardware/test_hw_board.py b/tests/hardware/test_hw_board.py new file mode 100644 index 0000000..966206c --- /dev/null +++ b/tests/hardware/test_hw_board.py @@ -0,0 +1,167 @@ +""" +Hardware integration test for board peripherals (LED, button, power). +Manual mode: Visual verification for LEDs, manual button press. +Test stand: Phototransistor verifies LED, button test uses GPIO toggle. +""" +from XRPLib.board import Board +from teststand import is_teststand, wait_if_manual, read_led_sensor, simulate_button_press +import time + +board = Board.get_default_board() + +passed = 0 +failed = 0 +skipped = 0 + + +def check(name, condition): + global passed, failed + if condition: + print(f" PASS: {name}") + passed += 1 + else: + print(f" FAIL: {name}") + failed += 1 + + +def skip(name): + global skipped + print(f" SKIP: {name}") + skipped += 1 + + +def test_led_on_off(): + """LED should turn on and off.""" + if is_teststand(): + baseline = read_led_sensor() + board.led_on() + time.sleep(0.1) + on_value = read_led_sensor() + board.led_off() + time.sleep(0.1) + off_value = read_led_sensor() + check(f"LED on detected (ADC {on_value} vs baseline {baseline})", + on_value > baseline + 1000) + check(f"LED off detected (ADC {off_value} near baseline {baseline})", + abs(off_value - baseline) < 2000) + else: + print(" LED should turn ON...") + board.led_on() + time.sleep(1) + print(" LED should turn OFF...") + board.led_off() + time.sleep(0.5) + check("LED on/off (visual check)", True) + + +def test_led_blink(): + """LED should blink at 5Hz.""" + if is_teststand(): + board.led_blink(5) + time.sleep(0.2) # let blink stabilize + # Sample ADC at ~100Hz for 1 second, count transitions + samples = [] + for _ in range(100): + samples.append(read_led_sensor()) + time.sleep(0.01) + board.led_off() + # Count transitions (high-to-low or low-to-high) + threshold = (max(samples) + min(samples)) // 2 + transitions = 0 + above = samples[0] > threshold + for s in samples[1:]: + now_above = s > threshold + if now_above != above: + transitions += 1 + above = now_above + # 5Hz blink = 10 transitions per second (±4 for timing variance) + check(f"LED blink: {transitions} transitions (expect 6-14)", 6 <= transitions <= 14) + else: + print(" LED should blink at 5Hz for 3 seconds...") + board.led_blink(5) + time.sleep(3) + board.led_off() + check("LED blink (visual check)", True) + + +def test_button(): + """Button press detection.""" + if is_teststand(): + # Verify button is not pressed initially + check("Button not pressed initially", not board.is_button_pressed()) + # Simulate press via GPIO + simulate_button_press(duration_ms=200) + # Note: button state only readable during the press window, + # so this test mainly verifies the GPIO wiring works. + # If SERVO_3 is not wired to the button, just skip. + check("Button GPIO toggle (no crash)", True) + else: + print(" Press the user button NOW...") + start = time.ticks_ms() + pressed = False + while time.ticks_diff(time.ticks_ms(), start) < 5000: + if board.is_button_pressed(): + pressed = True + break + time.sleep(0.01) + check("Button press detected", pressed) + + if pressed: + print(" Release the button...") + while board.is_button_pressed(): + time.sleep(0.01) + check("Button release detected", not board.is_button_pressed()) + + +def test_power_detect(): + """Power detection should return True when batteries connected.""" + powered = board.are_motors_powered() + check(f"Motors powered: {powered}", powered is True) + + +def test_rgb_led(): + """RGB LED should show colors (newer boards only).""" + try: + if is_teststand(): + # Phase 4: RGB color sensor verification + # For now, just verify the commands don't crash + board.set_rgb_led(255, 0, 0) + time.sleep(0.1) + board.set_rgb_led(0, 255, 0) + time.sleep(0.1) + board.set_rgb_led(0, 0, 255) + time.sleep(0.1) + board.set_rgb_led(0, 0, 0) + check("RGB LED commands executed (no crash)", True) + else: + print(" RGB LED: Red...") + board.set_rgb_led(255, 0, 0) + time.sleep(1) + print(" RGB LED: Green...") + board.set_rgb_led(0, 255, 0) + time.sleep(1) + print(" RGB LED: Blue...") + board.set_rgb_led(0, 0, 255) + time.sleep(1) + board.set_rgb_led(0, 0, 0) + check("RGB LED colors (visual check)", True) + except NotImplementedError: + print(" SKIP: RGB LED not available on this board") + + +print("=" * 40) +print("BOARD HARDWARE TESTS") +print("=" * 40) + +test_led_on_off() +test_led_blink() +test_button() +test_power_detect() +test_rgb_led() + +print() +result_msg = f"Results: {passed} passed, {failed} failed" +if skipped: + result_msg += f", {skipped} skipped" +result_msg += f" out of {passed + failed + skipped}" +print(result_msg) diff --git a/tests/hardware/test_hw_drivetrain.py b/tests/hardware/test_hw_drivetrain.py new file mode 100644 index 0000000..615a2a5 --- /dev/null +++ b/tests/hardware/test_hw_drivetrain.py @@ -0,0 +1,113 @@ +""" +Hardware integration test for drivetrain. +Run on the XRP robot on a flat, open surface. +Requires: batteries connected, power switch ON, clear space. +""" +from XRPLib.encoded_motor import EncodedMotor +from XRPLib.imu import IMU +from XRPLib.differential_drive import DifferentialDrive +from XRPLib.board import Board +from teststand import is_teststand, wait_if_manual +import time + +left = EncodedMotor.get_default_encoded_motor(1) +right = EncodedMotor.get_default_encoded_motor(2) +imu = IMU.get_default_imu() +drive = DifferentialDrive.get_default_differential_drive() +board = Board.get_default_board() + +passed = 0 +failed = 0 + + +def check(name, condition): + global passed, failed + if condition: + print(f" PASS: {name}") + passed += 1 + else: + print(f" FAIL: {name}") + failed += 1 + + +def test_straight(): + """Drive 30cm forward, verify encoder distance.""" + drive.reset_encoder_position() + result = drive.straight(30, max_effort=0.5, timeout=5) + left_dist = drive.get_left_encoder_position() + right_dist = drive.get_right_encoder_position() + avg_dist = (left_dist + right_dist) / 2 + check(f"Straight 30cm: traveled {avg_dist:.1f}cm", 25 < avg_dist < 35) + check("Straight returned True (completed)", result is True) + time.sleep(0.5) + + +def test_straight_reverse(): + """Drive 30cm backward.""" + drive.reset_encoder_position() + result = drive.straight(-30, max_effort=0.5, timeout=5) + avg_dist = (drive.get_left_encoder_position() + drive.get_right_encoder_position()) / 2 + check(f"Reverse 30cm: traveled {avg_dist:.1f}cm", -35 < avg_dist < -25) + time.sleep(0.5) + + +def test_turn_cw(): + """Turn 90 degrees clockwise.""" + imu.reset_yaw() + time.sleep(0.1) + result = drive.turn(90, max_effort=0.5, timeout=5) + yaw = imu.get_yaw() + check(f"Turn 90 CW: yaw={yaw:.1f} degrees", 80 < yaw < 100) + check("Turn returned True (completed)", result is True) + time.sleep(0.5) + + +def test_turn_ccw(): + """Turn 90 degrees counter-clockwise.""" + imu.reset_yaw() + time.sleep(0.1) + drive.turn(-90, max_effort=0.5, timeout=5) + yaw = imu.get_yaw() + check(f"Turn 90 CCW: yaw={yaw:.1f} degrees", -100 < yaw < -80) + time.sleep(0.5) + + +def test_timeout(): + """Very long distance should timeout.""" + start = time.ticks_ms() + result = drive.straight(10000, max_effort=0.3, timeout=2) + elapsed = time.ticks_diff(time.ticks_ms(), start) / 1000 + check(f"Timeout triggered in {elapsed:.1f}s", elapsed < 3) + check("Timeout returned False", result is False) + + +def test_square(): + """Drive a square and return near starting position.""" + drive.reset_encoder_position() + imu.reset_yaw() + side = 20 + for i in range(4): + drive.straight(side, max_effort=0.4, timeout=5) + drive.turn(90, max_effort=0.4, timeout=5) + time.sleep(0.2) + yaw = imu.get_yaw() + check(f"Square: final heading {yaw:.1f} degrees (expect ~360)", 340 < yaw < 380) + + +print("=" * 40) +print("DRIVETRAIN HARDWARE TESTS") +if not is_teststand(): + print("Place robot on flat surface.") + print("Press button to start.") +print("=" * 40) +wait_if_manual(board) + +test_straight() +test_straight_reverse() +test_turn_cw() +test_turn_ccw() +test_timeout() +test_square() + +print() +print(f"Results: {passed} passed, {failed} failed out of {passed + failed}") diff --git a/tests/hardware/test_hw_encoders.py b/tests/hardware/test_hw_encoders.py new file mode 100644 index 0000000..e95c7ec --- /dev/null +++ b/tests/hardware/test_hw_encoders.py @@ -0,0 +1,96 @@ +""" +Hardware integration test for encoders. +Run on the XRP robot with wheels elevated. +Requires: batteries connected, power switch ON. +""" +from XRPLib.encoded_motor import EncodedMotor +from XRPLib.encoder import Encoder +import time + +left = EncodedMotor.get_default_encoded_motor(1) +right = EncodedMotor.get_default_encoded_motor(2) + +passed = 0 +failed = 0 + + +def check(name, condition): + global passed, failed + if condition: + print(f" PASS: {name}") + passed += 1 + else: + print(f" FAIL: {name}") + failed += 1 + + +def test_count_direction(): + """Forward rotation should increase counts.""" + left.reset_encoder_position() + left.set_effort(0.3) + time.sleep(1) + left.set_effort(0) + time.sleep(0.2) + counts = left.get_position_counts() + check(f"Forward counts positive: {counts}", counts > 0) + + +def test_reverse_counts(): + """Backward rotation should decrease counts.""" + left.reset_encoder_position() + left.set_effort(-0.3) + time.sleep(1) + left.set_effort(0) + time.sleep(0.2) + counts = left.get_position_counts() + check(f"Reverse counts negative: {counts}", counts < 0) + + +def test_reset(): + """Reset should zero the position.""" + left.set_effort(0.3) + time.sleep(0.5) + left.set_effort(0) + time.sleep(0.2) + left.reset_encoder_position() + time.sleep(0.1) + counts = left.get_position_counts() + check(f"Reset zeroes position: {counts}", abs(counts) < 5) + + +def test_resolution(): + """One full wheel revolution should be ~585 counts.""" + left.reset_encoder_position() + # Drive slowly for approximately 1 revolution + left.set_effort(0.3) + while abs(left.get_position()) < 1.0: + time.sleep(0.01) + left.set_effort(0) + time.sleep(0.2) + counts = abs(left.get_position_counts()) + revs = left.get_position() + check(f"~1 revolution: {revs:.2f} revs, {counts} counts (expect ~585)", + 500 < counts < 700) + + +def test_stationary_consistency(): + """Multiple reads of stationary wheel should give same value.""" + left.set_effort(0) + time.sleep(0.5) + readings = [left.get_position_counts() for _ in range(10)] + spread = max(readings) - min(readings) + check(f"Stationary consistency: spread={spread} counts", spread <= 2) + + +print("=" * 40) +print("ENCODER HARDWARE TESTS") +print("=" * 40) + +test_count_direction() +test_reverse_counts() +test_reset() +test_resolution() +test_stationary_consistency() + +print() +print(f"Results: {passed} passed, {failed} failed out of {passed + failed}") diff --git a/tests/hardware/test_hw_imu.py b/tests/hardware/test_hw_imu.py new file mode 100644 index 0000000..762a0e3 --- /dev/null +++ b/tests/hardware/test_hw_imu.py @@ -0,0 +1,91 @@ +""" +Hardware integration test for IMU. +Setup: Board on flat, stable surface. Do not move during tests. +""" +from XRPLib.imu import IMU +from XRPLib.board import Board +from teststand import is_teststand, wait_if_manual +import time + +imu = IMU.get_default_imu() +board = Board.get_default_board() + +passed = 0 +failed = 0 + + +def check(name, condition): + global passed, failed + if condition: + print(f" PASS: {name}") + passed += 1 + else: + print(f" FAIL: {name}") + failed += 1 + + +def test_connected(): + check("IMU is connected", imu.is_connected()) + + +def test_gravity_z(): + """Z-axis should read ~1000mg (gravity) when flat.""" + z = imu.get_acc_z() + check(f"Gravity Z: {z:.0f}mg (expect ~1000)", 800 < z < 1200) + + +def test_gravity_xy(): + """X and Y should read near 0 when flat.""" + x = imu.get_acc_x() + y = imu.get_acc_y() + check(f"Gravity X: {x:.0f}mg (expect ~0)", abs(x) < 200) + check(f"Gravity Y: {y:.0f}mg (expect ~0)", abs(y) < 200) + + +def test_gyro_at_rest(): + """Gyroscope should read near 0 when stationary (after calibration).""" + rates = imu.get_gyro_rates() + check(f"Gyro X: {rates[0]:.0f}mdps (expect ~0)", abs(rates[0]) < 100) + check(f"Gyro Y: {rates[1]:.0f}mdps (expect ~0)", abs(rates[1]) < 100) + check(f"Gyro Z: {rates[2]:.0f}mdps (expect ~0)", abs(rates[2]) < 100) + + +def test_yaw_stable(): + """Yaw should not drift significantly over 5 seconds at rest.""" + imu.reset_yaw() + time.sleep(5) + yaw = imu.get_yaw() + check(f"Yaw drift over 5s: {yaw:.2f} degrees (expect < 3)", abs(yaw) < 3) + + +def test_temperature(): + """Temperature should be a reasonable room temperature.""" + temp = imu.temperature() + check(f"Temperature: {temp:.1f}C (expect 15-45)", 15 < temp < 45) + + +def test_acc_gyro_batch(): + """Batch read should return 2x3 array.""" + data = imu.get_acc_gyro_rates() + check("Batch read returns 2 rows", len(data) == 2) + check("Batch read returns 3 cols each", len(data[0]) == 3 and len(data[1]) == 3) + + +print("=" * 40) +print("IMU HARDWARE TESTS") +if not is_teststand(): + print("Keep board flat and still.") + print("Press button to start.") +print("=" * 40) +wait_if_manual(board) + +test_connected() +test_gravity_z() +test_gravity_xy() +test_gyro_at_rest() +test_yaw_stable() +test_temperature() +test_acc_gyro_batch() + +print() +print(f"Results: {passed} passed, {failed} failed out of {passed + failed}") diff --git a/tests/hardware/test_hw_motors.py b/tests/hardware/test_hw_motors.py new file mode 100644 index 0000000..d9a38af --- /dev/null +++ b/tests/hardware/test_hw_motors.py @@ -0,0 +1,128 @@ +""" +Hardware integration test for motors. +Run on the XRP robot with wheels elevated or on a flat surface. +Requires: batteries connected, power switch ON. + +Upload and run via: mpremote run tests/hardware/test_hw_motors.py +""" +from XRPLib.encoded_motor import EncodedMotor +import time + +left = EncodedMotor.get_default_encoded_motor(1) +right = EncodedMotor.get_default_encoded_motor(2) + +passed = 0 +failed = 0 + + +def check(name, condition): + global passed, failed + if condition: + print(f" PASS: {name}") + passed += 1 + else: + print(f" FAIL: {name}") + failed += 1 + + +def test_forward_effort(): + """Both motors spin forward at half effort.""" + left.reset_encoder_position() + right.reset_encoder_position() + left.set_effort(0.5) + right.set_effort(0.5) + time.sleep(1) + left.set_effort(0) + right.set_effort(0) + time.sleep(0.2) + check("Left motor moved forward", left.get_position() > 0) + check("Right motor moved forward", right.get_position() > 0) + + +def test_reverse_effort(): + """Both motors spin backward at half effort.""" + left.reset_encoder_position() + right.reset_encoder_position() + left.set_effort(-0.5) + right.set_effort(-0.5) + time.sleep(1) + left.set_effort(0) + right.set_effort(0) + time.sleep(0.2) + check("Left motor moved backward", left.get_position() < 0) + check("Right motor moved backward", right.get_position() < 0) + + +def test_independent_direction(): + """Left forward, right backward.""" + left.reset_encoder_position() + right.reset_encoder_position() + left.set_effort(0.5) + right.set_effort(-0.5) + time.sleep(1) + left.set_effort(0) + right.set_effort(0) + time.sleep(0.2) + check("Left forward, right backward", left.get_position() > 0 and right.get_position() < 0) + + +def test_brake(): + """Motor should resist rotation after braking.""" + left.set_effort(0.5) + time.sleep(0.5) + left.brake() + time.sleep(0.1) + pos1 = left.get_position() + time.sleep(0.5) + pos2 = left.get_position() + # Position should not change much after braking + check("Brake holds position", abs(pos2 - pos1) < 0.1) + left.coast() + + +def test_coast(): + """Motor should spin freely after coasting.""" + left.set_effort(0.5) + time.sleep(0.5) + left.coast() + time.sleep(0.1) + check("Coast releases motor (no crash)", True) + + +def test_speed_control(): + """Motor should reach target speed within tolerance.""" + left.reset_encoder_position() + left.set_speed(60) + time.sleep(2) + speed = left.get_speed() + left.set_speed(0) + left.set_effort(0) + check(f"Speed control: {speed:.1f} RPM (target 60)", 50 < speed < 70) + + +def test_zero_effort_stops(): + """Motor should stop at zero effort.""" + left.set_effort(0.5) + time.sleep(0.5) + left.set_effort(0) + time.sleep(0.5) + pos1 = left.get_position() + time.sleep(0.5) + pos2 = left.get_position() + check("Zero effort stops motor", abs(pos2 - pos1) < 0.1) + + +print("=" * 40) +print("MOTOR HARDWARE TESTS") +print("=" * 40) + +test_forward_effort() +test_reverse_effort() +test_independent_direction() +test_brake() +test_coast() +test_speed_control() +test_zero_effort_stops() + +print() +print(f"Results: {passed} passed, {failed} failed out of {passed + failed}") diff --git a/tests/hardware/test_hw_rangefinder.py b/tests/hardware/test_hw_rangefinder.py new file mode 100644 index 0000000..92ce750 --- /dev/null +++ b/tests/hardware/test_hw_rangefinder.py @@ -0,0 +1,81 @@ +""" +Hardware integration test for rangefinder. +Setup: Place a flat surface (wall/book) at a known distance from the sensor. +On test stand: wall is fixed at ~20cm. +""" +from XRPLib.rangefinder import Rangefinder +from XRPLib.board import Board +from teststand import is_teststand, wait_if_manual +import time + +rf = Rangefinder.get_default_rangefinder() +board = Board.get_default_board() + +passed = 0 +failed = 0 + + +def check(name, condition): + global passed, failed + if condition: + print(f" PASS: {name}") + passed += 1 + else: + print(f" FAIL: {name}") + failed += 1 + + +def test_first_reading(): + """First call to distance() should return a valid number.""" + d = rf.distance() + check(f"First reading is numeric: {d:.1f}cm", isinstance(d, (int, float))) + + +def test_reasonable_range(): + """Distance should be within sensor range (2-400cm) or MAX_VALUE.""" + d = rf.distance() + check(f"Reading in range: {d:.1f}cm", + (2 < d < 400) or d == rf.MAX_VALUE) + + +def test_stability(): + """10 readings at a fixed distance should have low variance.""" + time.sleep(0.5) # Let a few readings accumulate + readings = [] + for _ in range(10): + readings.append(rf.distance()) + time.sleep(0.1) + valid = [r for r in readings if r != rf.MAX_VALUE] + if len(valid) >= 5: + avg = sum(valid) / len(valid) + max_dev = max(abs(r - avg) for r in valid) + check(f"Stability: avg={avg:.1f}cm, max_deviation={max_dev:.1f}cm", + max_dev < 3.0) + else: + check("Stability: not enough valid readings", False) + + +def test_non_blocking_speed(): + """100 calls to distance() should complete quickly (non-blocking).""" + start = time.ticks_ms() + for _ in range(100): + rf.distance() + elapsed = time.ticks_diff(time.ticks_ms(), start) + check(f"100 reads in {elapsed}ms (expect < 200ms)", elapsed < 200) + + +print("=" * 40) +print("RANGEFINDER HARDWARE TESTS") +if not is_teststand(): + print("Point sensor at a surface ~20cm away.") + print("Press button to start.") +print("=" * 40) +wait_if_manual(board) + +test_first_reading() +test_reasonable_range() +test_stability() +test_non_blocking_speed() + +print() +print(f"Results: {passed} passed, {failed} failed out of {passed + failed}") diff --git a/tests/hardware/test_hw_reflectance.py b/tests/hardware/test_hw_reflectance.py new file mode 100644 index 0000000..8d74ec0 --- /dev/null +++ b/tests/hardware/test_hw_reflectance.py @@ -0,0 +1,73 @@ +""" +Hardware integration test for reflectance sensors. +Manual mode: Have white paper and dark surface available. +Test stand: Sliding plate with white/black halves is actuated automatically. +""" +from XRPLib.reflectance import Reflectance +from XRPLib.board import Board +from teststand import is_teststand, wait_if_manual, move_reflectance_slide +import time + +ref = Reflectance.get_default_reflectance() +board = Board.get_default_board() + +passed = 0 +failed = 0 + + +def check(name, condition): + global passed, failed + if condition: + print(f" PASS: {name}") + passed += 1 + else: + print(f" FAIL: {name}") + failed += 1 + + +def test_values_in_range(): + """Readings should be between 0 and 1.""" + left = ref.get_left() + right = ref.get_right() + check(f"Left in range: {left:.3f}", 0 <= left <= 1) + check(f"Right in range: {right:.3f}", 0 <= right <= 1) + + +def test_white_surface(): + """On white paper, readings should be low.""" + if is_teststand(): + move_reflectance_slide("white") + else: + print(" Place sensor over WHITE surface, press button...") + board.wait_for_button() + time.sleep(0.1) + left = ref.get_left() + right = ref.get_right() + check(f"White left={left:.3f} (expect < 0.4)", left < 0.4) + check(f"White right={right:.3f} (expect < 0.4)", right < 0.4) + + +def test_dark_surface(): + """On dark surface, readings should be high.""" + if is_teststand(): + move_reflectance_slide("black") + else: + print(" Place sensor over DARK surface, press button...") + board.wait_for_button() + time.sleep(0.1) + left = ref.get_left() + right = ref.get_right() + check(f"Dark left={left:.3f} (expect > 0.6)", left > 0.6) + check(f"Dark right={right:.3f} (expect > 0.6)", right > 0.6) + + +print("=" * 40) +print("REFLECTANCE HARDWARE TESTS") +print("=" * 40) + +test_values_in_range() +test_white_surface() +test_dark_surface() + +print() +print(f"Results: {passed} passed, {failed} failed out of {passed + failed}") diff --git a/tests/hardware/test_hw_servo.py b/tests/hardware/test_hw_servo.py new file mode 100644 index 0000000..1bd816a --- /dev/null +++ b/tests/hardware/test_hw_servo.py @@ -0,0 +1,79 @@ +""" +Hardware integration test for servos. +Manual mode: Visual verification of servo arm movement. +Test stand: Break-beam sensor verifies servo arm position. +""" +from XRPLib.servo import Servo +from XRPLib.board import Board +from teststand import is_teststand, wait_if_manual, read_servo_beam +import time + +servo = Servo.get_default_servo(1) +board = Board.get_default_board() + +passed = 0 +failed = 0 + + +def check(name, condition): + global passed, failed + if condition: + print(f" PASS: {name}") + passed += 1 + else: + print(f" FAIL: {name}") + failed += 1 + + +def test_angle_sweep(): + """Sweep through angles. Test stand uses break-beam sensor to verify movement.""" + try: + servo.set_angle(0) + time.sleep(0.5) + if is_teststand(): + beam_at_0 = read_servo_beam() + servo.set_angle(90) + time.sleep(0.5) + servo.set_angle(180) + time.sleep(0.5) + if is_teststand(): + beam_at_180 = read_servo_beam() + check("Servo moved (break-beam changed)", beam_at_0 != beam_at_180) + else: + check("Angle sweep 0->90->180 (visual check)", True) + servo.set_angle(90) + time.sleep(0.5) + except Exception as e: + check(f"Angle sweep failed: {e}", False) + + +def test_free(): + """Free should release the servo.""" + try: + servo.set_angle(90) + time.sleep(0.5) + servo.free() + time.sleep(0.5) + if is_teststand(): + # In teststand mode, just verify no crash — full free verification + # requires spring-loaded lever (Phase 3 enhancement) + check("Free command executed (no crash)", True) + else: + check("Free releases servo (verify by hand)", True) + except Exception as e: + check(f"Free failed: {e}", False) + + +print("=" * 40) +print("SERVO HARDWARE TESTS") +if not is_teststand(): + print("Watch servo arm for movement.") + print("Press button to start.") +print("=" * 40) +wait_if_manual(board) + +test_angle_sweep() +test_free() + +print() +print(f"Results: {passed} passed, {failed} failed out of {passed + failed}") diff --git a/tests/hardware/test_hw_timing.py b/tests/hardware/test_hw_timing.py new file mode 100644 index 0000000..6f46562 --- /dev/null +++ b/tests/hardware/test_hw_timing.py @@ -0,0 +1,94 @@ +""" +Hardware integration test for timer callback accuracy. +Verifies that timer callbacks fire at expected rates. +""" +from XRPLib.encoded_motor import EncodedMotor +from XRPLib.imu import IMU +from XRPLib.rangefinder import Rangefinder +from XRPLib.board import Board +from teststand import is_teststand, wait_if_manual +import time + +board = Board.get_default_board() + +passed = 0 +failed = 0 + + +def check(name, condition): + global passed, failed + if condition: + print(f" PASS: {name}") + passed += 1 + else: + print(f" FAIL: {name}") + failed += 1 + + +def test_motor_update_rate(): + """Motor _update should fire ~50 times per second.""" + motor = EncodedMotor.get_default_encoded_motor(1) + + # Monkey-patch _update to count calls + original_update = motor._update + count = [0] + + def counting_update(): + count[0] += 1 + original_update() + + motor.updateTimer.init(period=20, callback=lambda t: counting_update()) + time.sleep(1.0) + motor.updateTimer.init(period=20, callback=lambda t: motor._update()) # restore + + rate = count[0] + check(f"Motor update rate: {rate} Hz (expect 45-55)", 40 <= rate <= 60) + + +def test_imu_update_rate(): + """IMU _update should fire ~208 times per second.""" + imu = IMU.get_default_imu() + + count = [0] + original = imu._update_imu_readings + + def counting(): + count[0] += 1 + original() + + imu.update_timer.init(freq=imu.timer_frequency, callback=lambda t: counting()) + time.sleep(1.0) + imu._start_timer() # restore original + + rate = count[0] + check(f"IMU update rate: {rate} Hz (expect 180-230)", 150 <= rate <= 260) + + +def test_all_timers_simultaneously(): + """All timers running for 10 seconds without crash.""" + _ = EncodedMotor.get_default_encoded_motor(1) + _ = EncodedMotor.get_default_encoded_motor(2) + _ = IMU.get_default_imu() + _ = Rangefinder.get_default_rangefinder() + + print(" Running all timers for 10 seconds...") + try: + time.sleep(10) + check("All timers ran 10s without crash", True) + except Exception as e: + check(f"Timer crash: {e}", False) + + +print("=" * 40) +print("TIMING HARDWARE TESTS") +if not is_teststand(): + print("Press button to start.") +print("=" * 40) +wait_if_manual(board) + +test_motor_update_rate() +test_imu_update_rate() +test_all_timers_simultaneously() + +print() +print(f"Results: {passed} passed, {failed} failed out of {passed + failed}") diff --git a/tests/hardware/teststand.py b/tests/hardware/teststand.py new file mode 100644 index 0000000..06b6265 --- /dev/null +++ b/tests/hardware/teststand.py @@ -0,0 +1,79 @@ +""" +Test stand support module for automated hardware testing. + +When running on a test stand, tests skip manual intervention steps +(button presses, visual checks) and instead use automated sensors. + +Test stand mode is activated by placing a file called 'teststand_mode' +on the Pico's filesystem root: + mpremote fs touch :teststand_mode + +Sensor pin assignments (using spare Motor 3/4 and Servo 3/4 ports): + - LED phototransistor: MOTOR_3_ENCODER_A (ADC) + - Servo break-beam: MOTOR_3_ENCODER_B (digital in) + - Reflectance slide: SERVO_4 (PWM servo) + - Button test GPIO: SERVO_3 (optional, digital out) + - RGB color sensor: I2C bus (shared with IMU, addr 0x29) +""" +import os +import time + + +def is_teststand(): + """Check if running on an automated test stand.""" + try: + os.stat("/teststand_mode") + return True + except OSError: + return False + + +def wait_if_manual(board): + """In manual mode, wait for button press. In teststand mode, continue immediately.""" + if not is_teststand(): + board.wait_for_button() + + +# --------------------------------------------------------------------------- +# Test stand sensor helpers (Phase 2-4: only usable with instrumentation wired) +# --------------------------------------------------------------------------- + +def read_led_sensor(pin_name="MOTOR_3_ENCODER_A"): + """Read phototransistor aimed at the onboard LED. Returns ADC value 0-65535.""" + from machine import Pin, ADC + return ADC(Pin(pin_name)).read_u16() + + +def read_servo_beam(pin_name="MOTOR_3_ENCODER_B"): + """Read break-beam sensor at servo arm. Returns 0 if beam blocked, 1 if clear.""" + from machine import Pin + return Pin(pin_name, Pin.IN, Pin.PULL_UP).value() + + +def move_reflectance_slide(position, pin_name="SERVO_4"): + """ + Move the reflectance test surface slide to a position. + :param position: 'white' or 'black' + :param pin_name: Servo pin controlling the slide actuator + """ + from machine import Pin, PWM + servo = PWM(Pin(pin_name, Pin.OUT)) + servo.freq(50) + if position == "white": + servo.duty_ns(500000) # 0 degrees — white half under sensors + elif position == "black": + servo.duty_ns(2500000) # 200 degrees — black half under sensors + time.sleep(0.5) # allow slide to settle + + +def simulate_button_press(pin_name="SERVO_3", duration_ms=100): + """ + Optional: toggle the button pin for testing is_button_pressed(). + Requires SERVO_3 wired to BOARD_USER_BUTTON via 1kΩ resistor. + """ + from machine import Pin + pin = Pin(pin_name, Pin.OUT) + pin.value(0) # active low — simulate press + time.sleep_ms(duration_ms) + pin.value(1) # release + pin = Pin(pin_name, Pin.IN) # tri-state to avoid holding the line diff --git a/tests/mocks/__init__.py b/tests/mocks/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/tests/mocks/machine.py b/tests/mocks/machine.py new file mode 100644 index 0000000..cbee386 --- /dev/null +++ b/tests/mocks/machine.py @@ -0,0 +1,157 @@ +""" +Mock machine module for desktop unit testing. +Simulates Pin, ADC, PWM, Timer, I2C, disable_irq, enable_irq. +""" + + +class _PinBoard: + """Simulates Pin.board with named pin attributes.""" + BOARD_VIN_MEASURE = 26 + BOARD_USER_BUTTON = 22 + BOARD_NEOPIXEL = 4 + LED = 25 + MOTOR_L_IN_1 = 6 + MOTOR_L_IN_2 = 7 + MOTOR_R_IN_1 = 14 + MOTOR_R_IN_2 = 15 + MOTOR_L_ENCODER_A = 0 + MOTOR_L_ENCODER_B = 1 + MOTOR_R_ENCODER_A = 2 + MOTOR_R_ENCODER_B = 3 + MOTOR_3_IN_1 = 8 + MOTOR_3_IN_2 = 9 + MOTOR_3_ENCODER_A = 10 + MOTOR_3_ENCODER_B = 11 + MOTOR_4_IN_1 = 12 + MOTOR_4_IN_2 = 13 + MOTOR_4_ENCODER_A = 16 + MOTOR_4_ENCODER_B = 17 + RANGE_TRIGGER = 20 + RANGE_ECHO = 21 + LINE_L = 27 + LINE_R = 28 + I2C_SCL_1 = 19 + I2C_SDA_1 = 18 + SERVO_1 = 10 + SERVO_2 = 11 + SERVO_3 = 12 + SERVO_4 = 13 + + def __getattr__(self, name): + # Return any pin name as an integer so hasattr() works + return hash(name) % 30 + + +class Pin: + IN = 0 + OUT = 1 + PULL_UP = 1 + PULL_DOWN = 2 + IRQ_RISING = 1 + IRQ_FALLING = 2 + + board = _PinBoard() + + def __init__(self, pin_id=0, mode=None, pull=None, *args, **kwargs): + if isinstance(pin_id, str): + self._pin_id = getattr(Pin.board, pin_id, 0) + else: + self._pin_id = pin_id + self._mode = mode + self._value = 0 + self._irq_handler = None + + def value(self, v=None): + if v is not None: + self._value = v + return self._value + + def on(self): + self._value = 1 + + def off(self): + self._value = 0 + + def toggle(self): + self._value = 1 - self._value + + def irq(self, trigger=None, handler=None): + self._irq_handler = handler + + +class ADC: + def __init__(self, pin=None): + self._value = 0 + + def read_u16(self): + return self._value + + def _set_value(self, v): + self._value = v + + +class PWM: + def __init__(self, pin=None): + self._freq = 0 + self._duty_u16 = 0 + self._duty_ns = 0 + + def freq(self, f=None): + if f is not None: + self._freq = f + return self._freq + + def duty_u16(self, d=None): + if d is not None: + self._duty_u16 = d + return self._duty_u16 + + def duty_ns(self, d=None): + if d is not None: + self._duty_ns = d + return self._duty_ns + + +class Timer: + ONE_SHOT = 0 + PERIODIC = 1 + + def __init__(self, timer_id=-1): + self._id = timer_id + self._callback = None + self._period = None + self._freq = None + + def init(self, mode=PERIODIC, period=None, freq=None, callback=None): + self._mode = mode + self._period = period + self._freq = freq + self._callback = callback + + def deinit(self): + self._callback = None + self._period = None + self._freq = None + + +class I2C: + def __init__(self, id=0, scl=None, sda=None, freq=400000): + self._id = id + self._freq = freq + self._data = {} + + def writeto_mem(self, addr, reg, data): + self._data[(addr, reg)] = bytes(data) + + def readfrom_mem_into(self, addr, reg, buf): + data = self._data.get((addr, reg), bytes(len(buf))) + for i in range(min(len(buf), len(data))): + buf[i] = data[i] + + +def disable_irq(): + return 0 + + +def enable_irq(state): + pass diff --git a/tests/mocks/neopixel.py b/tests/mocks/neopixel.py new file mode 100644 index 0000000..144799f --- /dev/null +++ b/tests/mocks/neopixel.py @@ -0,0 +1,17 @@ +""" +Mock NeoPixel module for desktop unit testing. +""" + + +class NeoPixel: + def __init__(self, pin, count): + self._pixels = [(0, 0, 0)] * count + + def __setitem__(self, index, value): + self._pixels[index] = value + + def __getitem__(self, index): + return self._pixels[index] + + def write(self): + pass diff --git a/tests/mocks/rp2.py b/tests/mocks/rp2.py new file mode 100644 index 0000000..5fa8c2a --- /dev/null +++ b/tests/mocks/rp2.py @@ -0,0 +1,37 @@ +""" +Mock rp2 module for desktop unit testing. +""" + + +class PIO: + SHIFT_LEFT = 0 + SHIFT_RIGHT = 1 + + +class StateMachine: + def __init__(self, index, program=None, in_base=None, *args, **kwargs): + self._index = index + self._active = False + self._x = 0 + + def active(self, state=None): + if state is not None: + self._active = bool(state) + return self._active + + def get(self): + return self._x + + def exec(self, instruction): + if "set(x, 0)" in instruction: + self._x = 0 + + def _set_count(self, count): + self._x = count + + +def asm_pio(**kwargs): + """Decorator that returns the function unchanged for testing.""" + def decorator(func): + return func + return decorator diff --git a/tests/unit/__init__.py b/tests/unit/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/tests/unit/conftest.py b/tests/unit/conftest.py new file mode 100644 index 0000000..b847e34 --- /dev/null +++ b/tests/unit/conftest.py @@ -0,0 +1,190 @@ +""" +Pytest conftest that installs mock modules before any XRPLib imports. +Must run before any test that imports from XRPLib. +""" +import sys +import os +import types + +# Add project root to path +PROJECT_ROOT = os.path.abspath(os.path.join(os.path.dirname(__file__), "..", "..")) +MOCKS_DIR = os.path.join(os.path.dirname(__file__), "..", "mocks") + +sys.path.insert(0, PROJECT_ROOT) +sys.path.insert(0, MOCKS_DIR) + +# Install mock modules before any XRPLib code tries to import them +from tests.mocks import machine as mock_machine +from tests.mocks import rp2 as mock_rp2 +from tests.mocks import neopixel as mock_neopixel + +sys.modules["machine"] = mock_machine +sys.modules["rp2"] = mock_rp2 +sys.modules["neopixel"] = mock_neopixel + +# Mock uctypes for IMU +uctypes_mock = types.ModuleType("uctypes") +uctypes_mock.UINT8 = 0 +uctypes_mock.BFUINT8 = 0 +uctypes_mock.BF_POS = 8 +uctypes_mock.BF_LEN = 16 + + +def _mock_struct(addr, layout): + """Return an object whose fields are readable/writable attributes.""" + obj = types.SimpleNamespace() + for name in layout: + setattr(obj, name, 0) + return obj + + +def _mock_addressof(buf): + return id(buf) + + +uctypes_mock.struct = _mock_struct +uctypes_mock.addressof = _mock_addressof +sys.modules["uctypes"] = uctypes_mock + +# Mock gc.threshold (MicroPython-specific, not in CPython) +import gc +if not hasattr(gc, 'threshold'): + gc.threshold = lambda *args: None + +# Add MicroPython-specific time functions to the standard time module +import time +if not hasattr(time, 'ticks_ms'): + time.ticks_ms = lambda: int(time.time() * 1000) & 0x3FFFFFFF +if not hasattr(time, 'ticks_us'): + time.ticks_us = lambda: int(time.time() * 1_000_000) & 0x3FFFFFFF +if not hasattr(time, 'ticks_diff'): + def _ticks_diff(end, start): + # Simplified ticks_diff for testing (no wraparound in short tests) + return end - start + time.ticks_diff = _ticks_diff +if not hasattr(time, 'sleep_us'): + time.sleep_us = lambda us: time.sleep(us / 1_000_000) + +# Mock micropython module +micropython_mock = types.ModuleType("micropython") +micropython_mock.const = lambda x: x +sys.modules["micropython"] = micropython_mock + +# Mock phew and its submodules (for webserver) +phew_mock = types.ModuleType("phew") +phew_server = types.ModuleType("phew.server") +phew_template = types.ModuleType("phew.template") +phew_logging = types.ModuleType("phew.logging") +phew_access_point = types.ModuleType("phew.access_point") +phew_dns = types.ModuleType("phew.dns") + +phew_logging.LOG_INFO = 1 +phew_logging.log_file = "" +phew_logging.debug = lambda *a: None +phew_logging.info = lambda *a: None +phew_logging.warn = lambda *a: None +phew_logging.warning = lambda *a: None +phew_logging.error = lambda *a: None +phew_logging.disable_logging_types = lambda *a: None +phew_logging.enable_logging_types = lambda *a: None + +phew_server.run = lambda: None +phew_server.stop = lambda: None +phew_server.close = lambda: None +phew_server.redirect = lambda url: f"redirect:{url}" + +_routes = {} + + +def _route(path, methods=None): + def decorator(func): + _routes[path] = func + return func + return decorator + + +def _catchall(): + def decorator(func): + return func + return decorator + + +phew_server.route = _route +phew_server.catchall = _catchall + +phew_template.render_template = lambda *a: "" + +phew_mock.server = phew_server +phew_mock.template = phew_template +phew_mock.logging = phew_logging +phew_mock.dns = phew_dns +phew_mock.access_point = lambda ssid, pw=None: types.SimpleNamespace( + ifconfig=lambda: ("192.168.4.1", "", "", ""), + active=lambda v=None: True, + isconnected=lambda: True, + disconnect=lambda: None, +) + +phew_dns.run_catchall = lambda ip: None + +sys.modules["phew"] = phew_mock +sys.modules["phew.server"] = phew_server +sys.modules["phew.template"] = phew_template +sys.modules["phew.logging"] = phew_logging +sys.modules["phew.access_point"] = phew_access_point +sys.modules["phew.dns"] = phew_dns + +# Mock network module +network_mock = types.ModuleType("network") +network_mock.STA_IF = 0 +network_mock.AP_IF = 1 + + +class _MockWLAN: + def __init__(self, mode=0): + self._active = False + + def active(self, v=None): + if v is not None: + self._active = v + return self._active + + def connect(self, ssid, pw): + pass + + def isconnected(self): + return True + + def ifconfig(self): + return ("192.168.4.1", "", "", "") + + def disconnect(self): + pass + + +network_mock.WLAN = _MockWLAN +sys.modules["network"] = network_mock + +# Mock BLE for gamepad +ble_mock = types.ModuleType("ble") +blerepl_mock = types.ModuleType("ble.blerepl") + + +class _MockUart: + def set_data_callback(self, cb): + self._callback = cb + + +blerepl_mock.uart = _MockUart() +ble_mock.blerepl = blerepl_mock +sys.modules["ble"] = ble_mock +sys.modules["ble.blerepl"] = blerepl_mock + +# Patch sys.implementation._machine for board detection +if not hasattr(sys.implementation, "_machine"): + sys.implementation._machine = "Raspberry Pi Pico W with RP2350" + +# Suppress the XRPLib __init__.py version check +xrplib_init = types.ModuleType("XRPLib") +xrplib_init.__path__ = [os.path.join(PROJECT_ROOT, "XRPLib")] +sys.modules["XRPLib"] = xrplib_init diff --git a/tests/unit/test_board.py b/tests/unit/test_board.py new file mode 100644 index 0000000..9ffddd8 --- /dev/null +++ b/tests/unit/test_board.py @@ -0,0 +1,85 @@ +""" +Unit tests for Board class logic. +""" +import pytest +from XRPLib.board import Board + + +class TestBoardPowerDetection: + def test_motors_powered_high_adc(self): + b = Board() + b.on_switch._set_value(30000) + assert b.are_motors_powered() is True + + def test_motors_not_powered_low_adc(self): + b = Board() + b.on_switch._set_value(10000) + assert b.are_motors_powered() is False + + def test_motors_powered_boundary(self): + b = Board() + b.on_switch._set_value(20001) + assert b.are_motors_powered() is True + + def test_motors_not_powered_at_boundary(self): + b = Board() + b.on_switch._set_value(20000) + assert b.are_motors_powered() is False + + +class TestBoardButton: + def test_button_not_pressed(self): + b = Board() + b.button._value = 1 # Pull-up: high when not pressed + assert b.is_button_pressed() is False + + def test_button_pressed(self): + b = Board() + b.button._value = 0 # Active low + assert b.is_button_pressed() is True + + +class TestBoardLED: + def test_led_on(self): + b = Board() + b.led_on() + assert b.led._value == 1 + assert b.is_led_blinking is False + + def test_led_off(self): + b = Board() + b.led_on() + b.led_off() + assert b.led._value == 0 + assert b.is_led_blinking is False + + def test_led_blink_starts(self): + b = Board() + b.led_blink(5) + assert b.is_led_blinking is True + assert b._virt_timer._freq == 10 # 5Hz * 2 + + def test_led_blink_zero_stops(self): + b = Board() + b.led_blink(5) + b.led_blink(0) + assert b.is_led_blinking is False + + +class TestBoardRGBLED: + def test_set_rgb_on_supported_board(self): + b = Board() + # Manually add rgb_led (simulating a board that supports it) + from tests.mocks.neopixel import NeoPixel + from tests.mocks.machine import Pin + b.rgb_led = NeoPixel(Pin(), 1) + b.set_rgb_led(255, 0, 128) + assert b.rgb_led[0] == (255, 0, 128) + + def test_set_rgb_raises_on_beta(self): + b = Board() + # Remove rgb_led if it exists to simulate beta board + if "rgb_led" in b.__dict__: + del b.rgb_led + with pytest.raises(NotImplementedError): + b.set_rgb_led(255, 0, 0) diff --git a/tests/unit/test_differential_drive.py b/tests/unit/test_differential_drive.py new file mode 100644 index 0000000..ee76e17 --- /dev/null +++ b/tests/unit/test_differential_drive.py @@ -0,0 +1,74 @@ +""" +Unit tests for DifferentialDrive math (no real hardware motion). +""" +import math +import pytest +from XRPLib.encoded_motor import EncodedMotor +from XRPLib.differential_drive import DifferentialDrive + + +@pytest.fixture +def drive(): + left = EncodedMotor.get_default_encoded_motor(1) + right = EncodedMotor.get_default_encoded_motor(2) + return DifferentialDrive(left, right, imu=None, wheel_diam=6.0, wheel_track=15.5) + + +class TestArcadeDrive: + def test_zero_input_stops(self, drive): + drive.arcade(0, 0) + # Both motors should be set to 0 + + def test_straight_forward(self, drive): + drive.arcade(1.0, 0) + # Both motors should get equal positive effort + + def test_pure_turn(self, drive): + drive.arcade(0, 1.0) + # Left and right should be opposite signs + + def test_scaling_preserves_ratio(self, drive): + # The arcade scaling formula: scale = max(|s|,|t|) / (|s|+|t|) + s, t = 0.6, 0.4 + scale = max(abs(s), abs(t)) / (abs(s) + abs(t)) + left = (s - t) * scale + right = (s + t) * scale + # Both should be within [-1, 1] + assert -1 <= left <= 1 + assert -1 <= right <= 1 + + def test_full_forward_full_turn_bounded(self): + """Verify the arcade formula keeps values in [-1, 1].""" + for s in [-1.0, -0.5, 0, 0.5, 1.0]: + for t in [-1.0, -0.5, 0, 0.5, 1.0]: + if s == 0 and t == 0: + continue + scale = max(abs(s), abs(t)) / (abs(s) + abs(t)) + left = (s - t) * scale + right = (s + t) * scale + assert -1.001 <= left <= 1.001, f"left={left} for s={s}, t={t}" + assert -1.001 <= right <= 1.001, f"right={right} for s={s}, t={t}" + + +class TestEncoderPositionToCm: + def test_encoder_position_to_cm(self, drive): + """Verify the conversion from encoder revolutions to cm.""" + # 1 revolution * pi * wheel_diam = pi * 6.0 = 18.85 cm + wheel_diam = 6.0 + one_rev_cm = math.pi * wheel_diam + assert one_rev_cm == pytest.approx(18.85, abs=0.01) + + def test_track_width_default(self, drive): + assert drive.track_width == 15.5 + + def test_wheel_diam_default(self, drive): + assert drive.wheel_diam == 6.0 + + +class TestDrivetrainStop: + def test_stop_disables_speed_control(self, drive): + drive.left_motor.set_speed(60) + drive.right_motor.set_speed(60) + drive.stop() + assert drive.left_motor.target_speed is None + assert drive.right_motor.target_speed is None diff --git a/tests/unit/test_encoded_motor.py b/tests/unit/test_encoded_motor.py new file mode 100644 index 0000000..15723fa --- /dev/null +++ b/tests/unit/test_encoded_motor.py @@ -0,0 +1,67 @@ +""" +Unit tests for EncodedMotor. +""" +import pytest +from XRPLib.encoded_motor import EncodedMotor + + +class TestEncodedMotorSingleton: + def test_get_default_motor_returns_same_instance(self): + m1 = EncodedMotor.get_default_encoded_motor(1) + m2 = EncodedMotor.get_default_encoded_motor(1) + assert m1 is m2 + + def test_different_indices_return_different_instances(self): + m1 = EncodedMotor.get_default_encoded_motor(1) + m2 = EncodedMotor.get_default_encoded_motor(2) + assert m1 is not m2 + + def test_invalid_index_bug(self): + """Documents the bug: invalid index returns Exception instead of raising it.""" + result = EncodedMotor.get_default_encoded_motor(99) + # This should raise, but currently returns an Exception object + assert isinstance(result, Exception) + + +class TestEncodedMotorEffort: + def test_set_effort_zero_coast(self): + m = EncodedMotor.get_default_encoded_motor(1) + m.brake_at_zero = False + m.set_effort(0) + # Should call motor.set_effort(0), not brake + + def test_set_effort_zero_brake(self): + m = EncodedMotor.get_default_encoded_motor(1) + m.set_zero_effort_behavior(EncodedMotor.ZERO_EFFORT_BREAK) + m.set_effort(0) + # Should call brake() when effort is 0 + + def test_set_effort_nonzero_ignores_brake_setting(self): + m = EncodedMotor.get_default_encoded_motor(1) + m.set_zero_effort_behavior(EncodedMotor.ZERO_EFFORT_BREAK) + m.set_effort(0.5) + # Should set effort normally even with brake_at_zero set + + +class TestEncodedMotorSpeed: + def test_speed_conversion_formula(self): + """Verify the RPM to counts/20ms conversion.""" + from XRPLib.encoder import Encoder + resolution = Encoder.resolution # 585 + # 60 RPM = 1 rev/sec = 585 counts/sec = 585/50 = 11.7 counts/20ms + rpm = 60 + expected_counts_per_20ms = rpm * resolution / (60 * 50) + assert expected_counts_per_20ms == pytest.approx(11.7) + + def test_set_speed_none_stops(self): + m = EncodedMotor.get_default_encoded_motor(1) + m.set_speed(60) + assert m.target_speed is not None + m.set_speed(None) + assert m.target_speed is None + + def test_set_speed_zero_stops(self): + m = EncodedMotor.get_default_encoded_motor(1) + m.set_speed(60) + m.set_speed(0) + assert m.target_speed is None diff --git a/tests/unit/test_encoder.py b/tests/unit/test_encoder.py new file mode 100644 index 0000000..9a5b7ad --- /dev/null +++ b/tests/unit/test_encoder.py @@ -0,0 +1,44 @@ +""" +Unit tests for Encoder resolution and position math. +""" +import pytest +from XRPLib.encoder import Encoder + + +class TestEncoderResolution: + def test_gear_ratio(self): + expected = (30/14) * (28/16) * (36/9) * (26/8) + assert Encoder._gear_ratio == pytest.approx(expected) + assert Encoder._gear_ratio == pytest.approx(48.75) + + def test_resolution(self): + assert Encoder.resolution == pytest.approx(585.0) + + def test_counts_per_motor_shaft_revolution(self): + assert Encoder._counts_per_motor_shaft_revolution == 12 + + +class TestEncoderPosition: + def test_get_position_zero(self): + enc = Encoder(0, "MOTOR_L_ENCODER_A", "MOTOR_L_ENCODER_B") + pos = enc.get_position() + assert pos == 0.0 + + def test_get_position_one_revolution(self): + enc = Encoder(1, "MOTOR_R_ENCODER_A", "MOTOR_R_ENCODER_B") + enc.sm._set_count(585) + pos = enc.get_position() + assert pos == pytest.approx(1.0) + + def test_get_position_counts_negative(self): + enc = Encoder(2, "MOTOR_3_ENCODER_A", "MOTOR_3_ENCODER_B") + # Simulate negative count via 2^32 wraparound + enc.sm._set_count(2**32 - 100) + counts = enc.get_position_counts() + assert counts == -100 + + def test_reset_encoder_position(self): + enc = Encoder(3, "MOTOR_4_ENCODER_A", "MOTOR_4_ENCODER_B") + enc.sm._set_count(1000) + enc.reset_encoder_position() + assert enc.get_position_counts() == 0 diff --git a/tests/unit/test_gamepad.py b/tests/unit/test_gamepad.py new file mode 100644 index 0000000..49542f7 --- /dev/null +++ b/tests/unit/test_gamepad.py @@ -0,0 +1,80 @@ +""" +Unit tests for Gamepad data parsing. +""" +import pytest +from XRPLib.gamepad import Gamepad + + +class TestGamepadParsing: + def setup_method(self): + self.gp = Gamepad() + # Reset shared class data + for i in range(len(self.gp._joyData)): + self.gp._joyData[i] = 0.0 + + def test_valid_packet_joystick(self): + # Packet: header=0x55, length=2, index=0 (X1), value=255 (full right) + data = bytearray([0x55, 2, 0, 255]) + self.gp._data_callback(data) + # value = round(255/127.5 - 1, 2) = round(1.0, 2) = 1.0 + assert self.gp._joyData[0] == pytest.approx(1.0) + + def test_valid_packet_center(self): + # value = 127 -> round(127/127.5 - 1, 2) = round(-0.004, 2) = 0.0 + data = bytearray([0x55, 2, 0, 127]) + self.gp._data_callback(data) + assert abs(self.gp._joyData[0]) < 0.01 + + def test_valid_packet_minimum(self): + # value = 0 -> round(0/127.5 - 1, 2) = -1.0 + data = bytearray([0x55, 2, 0, 0]) + self.gp._data_callback(data) + assert self.gp._joyData[0] == pytest.approx(-1.0) + + def test_multiple_axes_in_one_packet(self): + # length=4: two axis pairs + data = bytearray([0x55, 4, 0, 255, 1, 0]) + self.gp._data_callback(data) + assert self.gp._joyData[0] == pytest.approx(1.0) + assert self.gp._joyData[1] == pytest.approx(-1.0) + + def test_button_press(self): + # Button A (index 4), value 255 (pressed) + data = bytearray([0x55, 2, 4, 255]) + self.gp._data_callback(data) + assert self.gp._joyData[4] == pytest.approx(1.0) + + def test_invalid_header_ignored(self): + data = bytearray([0xAA, 2, 0, 255]) + self.gp._data_callback(data) + assert self.gp._joyData[0] == 0.0 + + def test_wrong_length_ignored(self): + # Header says length=4, but only 4 bytes total (should be 6) + data = bytearray([0x55, 4, 0, 255]) + self.gp._data_callback(data) + assert self.gp._joyData[0] == 0.0 + + +class TestGamepadAPI: + def setup_method(self): + self.gp = Gamepad() + for i in range(len(self.gp._joyData)): + self.gp._joyData[i] = 0.0 + + def test_get_value_negated(self): + """get_value returns negated value for user convention.""" + self.gp._joyData[0] = 1.0 + assert self.gp.get_value(0) == -1.0 + + def test_is_button_pressed_true(self): + self.gp._joyData[Gamepad.BUTTON_A] = 1.0 + assert self.gp.is_button_pressed(Gamepad.BUTTON_A) is True + + def test_is_button_pressed_false(self): + self.gp._joyData[Gamepad.BUTTON_A] = 0.0 + assert self.gp.is_button_pressed(Gamepad.BUTTON_A) is False + + def test_is_button_pressed_negative(self): + self.gp._joyData[Gamepad.BUTTON_B] = -0.5 + assert self.gp.is_button_pressed(Gamepad.BUTTON_B) is False diff --git a/tests/unit/test_imu_math.py b/tests/unit/test_imu_math.py new file mode 100644 index 0000000..a3223d1 --- /dev/null +++ b/tests/unit/test_imu_math.py @@ -0,0 +1,135 @@ +""" +Unit tests for IMU data conversion math. +Tests the pure math functions without needing real I2C. +""" +import pytest +from XRPLib.imu import IMU + + +@pytest.fixture +def imu(): + """Create an IMU instance with mocked I2C.""" + return IMU.__new__(IMU) + + +class TestInt16: + def setup_method(self): + self.imu = IMU.__new__(IMU) + + def test_positive(self): + assert self.imu._int16(100) == 100 + + def test_zero(self): + assert self.imu._int16(0) == 0 + + def test_max_positive(self): + assert self.imu._int16(0x7FFF) == 32767 + + def test_negative_boundary(self): + assert self.imu._int16(0x8000) == -32768 + + def test_full_negative(self): + assert self.imu._int16(0xFFFF) == -1 + + def test_mid_negative(self): + assert self.imu._int16(0xFF00) == -256 + + +class TestRawConversions: + def setup_method(self): + self.imu = IMU.__new__(IMU) + self.imu._acc_scale_factor = 1 + self.imu._gyro_scale_factor = 1 + + def test_raw_to_mg_zero(self): + raw = bytearray([0, 0]) + assert self.imu._raw_to_mg(raw) == 0 + + def test_raw_to_mg_positive(self): + # Little-endian: [low, high] + raw = bytearray([0x00, 0x01]) # 256 + result = self.imu._raw_to_mg(raw) + # 256 * 0.061 (LSM_MG_PER_LSB_2G) * 1 (scale factor) + assert result == pytest.approx(256 * 0.061, abs=0.1) + + def test_raw_to_mg_negative(self): + raw = bytearray([0x00, 0xFF]) # 0xFF00 = -256 as int16 + result = self.imu._raw_to_mg(raw) + assert result == pytest.approx(-256 * 0.061, abs=0.1) + + def test_raw_to_mg_with_scale_factor(self): + self.imu._acc_scale_factor = 8 # 16g mode + raw = bytearray([0x00, 0x01]) # 256 + result = self.imu._raw_to_mg(raw) + assert result == pytest.approx(256 * 0.061 * 8, abs=0.1) + + def test_raw_to_mdps_zero(self): + raw = bytearray([0, 0]) + assert self.imu._raw_to_mdps(raw) == 0 + + def test_raw_to_mdps_positive(self): + raw = bytearray([0x00, 0x01]) # 256 + result = self.imu._raw_to_mdps(raw) + # 256 * 4.375 (LSM_MDPS_PER_LSB_125DPS) * 1 + assert result == pytest.approx(256 * 4.375, abs=1) + + +class TestAngleIntegration: + def test_pitch_starts_at_zero(self): + imu = IMU.__new__(IMU) + imu.running_pitch = 0 + assert imu.get_pitch() == 0 + + def test_yaw_set_and_get(self): + imu = IMU.__new__(IMU) + imu.running_yaw = 0 + imu.set_yaw(45.0) + assert imu.get_yaw() == 45.0 + + def test_heading_bounded(self): + imu = IMU.__new__(IMU) + imu.running_yaw = 450.0 + assert imu.get_heading() == pytest.approx(90.0) + + def test_heading_negative(self): + imu = IMU.__new__(IMU) + imu.running_yaw = -90.0 + heading = imu.get_heading() + assert 0 <= heading < 360 + assert heading == pytest.approx(270.0) + + def test_reset_yaw(self): + imu = IMU.__new__(IMU) + imu.running_yaw = 123.0 + imu.reset_yaw() + assert imu.get_yaw() == 0 + + def test_reset_pitch(self): + imu = IMU.__new__(IMU) + imu.running_pitch = 45.0 + imu.reset_pitch() + assert imu.get_pitch() == 0 + + def test_reset_roll(self): + imu = IMU.__new__(IMU) + imu.running_roll = -30.0 + imu.reset_roll() + assert imu.get_roll() == 0 + + +class TestScaleFactors: + def test_acc_scale_factor_2g(self): + # '2g' -> int('2') // 2 = 1 + assert int('2') // 2 == 1 + + def test_acc_scale_factor_16g(self): + # '16g' -> int('16') // 2 = 8 + assert int('16') // 2 == 8 + + def test_gyro_scale_factor_125dps(self): + # '125dps' -> int('125') // 125 = 1 + assert int('125') // 125 == 1 + + def test_gyro_scale_factor_2000dps(self): + # '2000dps' -> int('2000') // 125 = 16 + assert int('2000') // 125 == 16 diff --git a/tests/unit/test_motor.py b/tests/unit/test_motor.py new file mode 100644 index 0000000..02f5b38 --- /dev/null +++ b/tests/unit/test_motor.py @@ -0,0 +1,101 @@ +""" +Unit tests for SinglePWMMotor and DualPWMMotor. +""" +import pytest +from XRPLib.motor import SinglePWMMotor, DualPWMMotor + + +class TestSinglePWMMotor: + def test_effort_zero(self): + m = SinglePWMMotor("MOTOR_L_IN_1", "MOTOR_L_IN_2") + m.set_effort(0) + assert m._in2SpeedPin.duty_u16() == 0 + + def test_effort_positive(self): + m = SinglePWMMotor("MOTOR_L_IN_1", "MOTOR_L_IN_2") + m.set_effort(0.5) + expected = int(0.5 * 65534) + assert m._in2SpeedPin.duty_u16() == expected + assert m._in1DirPin._value == 0 # forward direction + + def test_effort_negative(self): + m = SinglePWMMotor("MOTOR_L_IN_1", "MOTOR_L_IN_2") + m.set_effort(-0.5) + expected = int(0.5 * 65534) + assert m._in2SpeedPin.duty_u16() == expected + assert m._in1DirPin._value == 1 # reverse direction + + def test_effort_clamped_above_one(self): + m = SinglePWMMotor("MOTOR_L_IN_1", "MOTOR_L_IN_2") + m.set_effort(1.5) + assert m._in2SpeedPin.duty_u16() == 65534 # clamped to 1.0 + + def test_effort_clamped_below_neg_one(self): + m = SinglePWMMotor("MOTOR_L_IN_1", "MOTOR_L_IN_2") + m.set_effort(-1.5) + assert m._in2SpeedPin.duty_u16() == 65534 # clamped to 1.0 magnitude + + def test_flip_dir(self): + m = SinglePWMMotor("MOTOR_L_IN_1", "MOTOR_L_IN_2", flip_dir=True) + m.set_effort(0.5) + assert m._in1DirPin._value == 1 # inverted: forward becomes 1 + + def test_brake(self): + m = SinglePWMMotor("MOTOR_L_IN_1", "MOTOR_L_IN_2") + m.brake() + assert m._in2SpeedPin.duty_u16() == 65535 + + def test_coast(self): + m = SinglePWMMotor("MOTOR_L_IN_1", "MOTOR_L_IN_2") + m.set_effort(0.5) + m.coast() + assert m._in2SpeedPin.duty_u16() == 0 + + def test_pwm_frequency(self): + m = SinglePWMMotor("MOTOR_L_IN_1", "MOTOR_L_IN_2") + assert m._in2SpeedPin.freq() == 50 + + +class TestDualPWMMotor: + def test_effort_positive_no_flip(self): + m = DualPWMMotor("MOTOR_R_IN_1", "MOTOR_R_IN_2") + m.set_effort(0.5) + # effort > 0, flip_dir=False: in1Pwm = False ^ False = False + # So in2 gets the duty, in1 is 0 + assert m._in2BackwardPin.duty_u16() == int(0.5 * 65535) + assert m._in1ForwardPin.duty_u16() == 0 + + def test_effort_negative_no_flip(self): + m = DualPWMMotor("MOTOR_R_IN_1", "MOTOR_R_IN_2") + m.set_effort(-0.5) + # effort < 0, flip_dir=False: in1Pwm = True ^ False = True + assert m._in1ForwardPin.duty_u16() == int(0.5 * 65535) + assert m._in2BackwardPin.duty_u16() == 0 + + def test_flip_dir(self): + m = DualPWMMotor("MOTOR_R_IN_1", "MOTOR_R_IN_2", flip_dir=True) + m.set_effort(0.5) + # effort > 0, flip_dir=True: in1Pwm = False ^ True = True + assert m._in1ForwardPin.duty_u16() == int(0.5 * 65535) + assert m._in2BackwardPin.duty_u16() == 0 + + def test_brake(self): + m = DualPWMMotor("MOTOR_R_IN_1", "MOTOR_R_IN_2") + m.brake() + assert m._in1ForwardPin.duty_u16() == 65535 + assert m._in2BackwardPin.duty_u16() == 65535 + + def test_coast(self): + m = DualPWMMotor("MOTOR_R_IN_1", "MOTOR_R_IN_2") + m.set_effort(0.5) + m.coast() + assert m._in1ForwardPin.duty_u16() == 0 + assert m._in2BackwardPin.duty_u16() == 0 + + def test_no_input_clamping_bug(self): + """Documents the current bug: DualPWMMotor doesn't clamp effort > 1.0""" + m = DualPWMMotor("MOTOR_R_IN_1", "MOTOR_R_IN_2") + m.set_effort(1.5) + # This will produce duty > 65535, which is the bug documented in the code review + duty = m._in2BackwardPin.duty_u16() + assert duty > 65535 # confirms the bug exists diff --git a/tests/unit/test_motor_group.py b/tests/unit/test_motor_group.py new file mode 100644 index 0000000..1026c77 --- /dev/null +++ b/tests/unit/test_motor_group.py @@ -0,0 +1,91 @@ +""" +Unit tests for MotorGroup aggregation logic. +""" +import pytest +from unittest.mock import MagicMock +from XRPLib.motor_group import MotorGroup + + +def _make_mock_motor(position=0.0, position_counts=0, speed=0.0): + m = MagicMock() + m.get_position.return_value = position + m.get_position_counts.return_value = position_counts + m.get_speed.return_value = speed + return m + + +class TestMotorGroupAverages: + def test_average_position(self): + m1 = _make_mock_motor(position=1.0) + m2 = _make_mock_motor(position=3.0) + g = MotorGroup(m1, m2) + assert g.get_position() == pytest.approx(2.0) + + def test_average_position_counts(self): + m1 = _make_mock_motor(position_counts=100) + m2 = _make_mock_motor(position_counts=200) + g = MotorGroup(m1, m2) + assert g.get_position_counts() == 150 + + def test_average_speed(self): + m1 = _make_mock_motor(speed=60.0) + m2 = _make_mock_motor(speed=40.0) + g = MotorGroup(m1, m2) + assert g.get_speed() == pytest.approx(50.0) + + def test_single_motor(self): + m1 = _make_mock_motor(position=5.0) + g = MotorGroup(m1) + assert g.get_position() == pytest.approx(5.0) + + +class TestMotorGroupDelegation: + def test_set_effort_all(self): + m1 = _make_mock_motor() + m2 = _make_mock_motor() + g = MotorGroup(m1, m2) + g.set_effort(0.7) + m1.set_effort.assert_called_with(0.7) + m2.set_effort.assert_called_with(0.7) + + def test_reset_encoder_all(self): + m1 = _make_mock_motor() + m2 = _make_mock_motor() + g = MotorGroup(m1, m2) + g.reset_encoder_position() + m1.reset_encoder_position.assert_called_once() + m2.reset_encoder_position.assert_called_once() + + def test_set_speed_all(self): + m1 = _make_mock_motor() + m2 = _make_mock_motor() + g = MotorGroup(m1, m2) + g.set_speed(60.0) + m1.set_speed.assert_called_with(60.0) + m2.set_speed.assert_called_with(60.0) + + +class TestMotorGroupAddRemove: + def test_add_motor(self): + m1 = _make_mock_motor() + g = MotorGroup(m1) + assert len(g.motors) == 1 + m2 = _make_mock_motor() + g.add_motor(m2) + assert len(g.motors) == 2 + + def test_remove_motor(self): + m1 = _make_mock_motor() + m2 = _make_mock_motor() + g = MotorGroup(m1, m2) + g.remove_motor(m1) + assert len(g.motors) == 1 + assert g.motors[0] is m2 + + def test_remove_nonexistent_motor(self): + m1 = _make_mock_motor() + g = MotorGroup(m1) + m2 = _make_mock_motor() + # Should not raise, just print + g.remove_motor(m2) + assert len(g.motors) == 1 diff --git a/tests/unit/test_pid.py b/tests/unit/test_pid.py new file mode 100644 index 0000000..e9291a8 --- /dev/null +++ b/tests/unit/test_pid.py @@ -0,0 +1,140 @@ +""" +Unit tests for PID controller logic. +""" +import time +import pytest +from XRPLib.pid import PID + + +class TestPIDBasic: + def test_proportional_only(self): + pid = PID(kp=1.0, ki=0, kd=0, min_output=0, max_output=10) + output = pid.update(5.0) + assert output == pytest.approx(5.0, abs=0.1) + + def test_proportional_negative_error(self): + pid = PID(kp=1.0, ki=0, kd=0, min_output=0, max_output=10) + output = pid.update(-3.0) + assert output == pytest.approx(-3.0, abs=0.1) + + def test_proportional_scaling(self): + pid = PID(kp=0.5, ki=0, kd=0, min_output=0, max_output=10) + output = pid.update(4.0) + assert output == pytest.approx(2.0, abs=0.1) + + def test_zero_error(self): + pid = PID(kp=1.0, ki=0, kd=0, min_output=0, max_output=10) + # With min_output=0, zero error should give zero-ish output + output = pid.update(0.0) + assert abs(output) < 0.01 + + +class TestPIDOutputBounds: + def test_max_output_clamping(self): + pid = PID(kp=10.0, ki=0, kd=0, min_output=0, max_output=1.0) + output = pid.update(5.0) + assert output == pytest.approx(1.0) + + def test_max_output_clamping_negative(self): + pid = PID(kp=10.0, ki=0, kd=0, min_output=0, max_output=1.0) + output = pid.update(-5.0) + assert output == pytest.approx(-1.0) + + def test_min_output_positive(self): + pid = PID(kp=0.001, ki=0, kd=0, min_output=0.3, max_output=1.0) + output = pid.update(1.0) + # Small kp * error = 0.001, but min_output forces it to 0.3 + assert output >= 0.3 + + def test_min_output_negative(self): + pid = PID(kp=0.001, ki=0, kd=0, min_output=0.3, max_output=1.0) + output = pid.update(-1.0) + assert output <= -0.3 + + +class TestPIDIntegral: + def test_integral_accumulates(self): + pid = PID(kp=0, ki=1.0, kd=0, min_output=0, max_output=100) + # Call update multiple times with constant error + for _ in range(10): + output = pid.update(1.0) + time.sleep(0.01) + # Integral should have accumulated, output should be positive and growing + assert output > 0 + + def test_integral_windup_cap(self): + pid = PID(kp=0, ki=1.0, kd=0, min_output=0, max_output=100, max_integral=5.0) + # Push integral hard + for _ in range(100): + pid.update(10.0) + time.sleep(0.01) + # Integral term should be capped at max_integral * ki = 5.0 + assert pid.prev_integral <= 5.0 + assert pid.prev_integral >= -5.0 + + def test_integral_negative(self): + pid = PID(kp=0, ki=1.0, kd=0, min_output=0, max_output=100, max_integral=50) + for _ in range(10): + pid.update(-1.0) + time.sleep(0.01) + assert pid.prev_integral < 0 + + +class TestPIDDerivative: + def test_derivative_responds_to_change(self): + pid = PID(kp=0, ki=0, kd=1.0, min_output=0, max_output=100) + pid.update(0.0) + time.sleep(0.01) + output = pid.update(10.0) + # Error jumped from 0 to 10, derivative should be large positive + assert output > 0 + + +class TestPIDRateLimiting: + def test_max_derivative_limits_output_change(self): + pid = PID(kp=10.0, ki=0, kd=0, min_output=0, max_output=100, max_derivative=1.0) + pid.update(0.0) + time.sleep(0.05) + output = pid.update(100.0) + # Without rate limiting, output would be 100. With max_derivative=1.0, + # it should be limited to prev_output + max_derivative * dt + assert output < 10.0 + + +class TestPIDTolerance: + def test_not_done_initially(self): + pid = PID(tolerance=0.5, tolerance_count=3) + pid.update(10.0) + assert not pid.is_done() + + def test_done_after_tolerance_count(self): + pid = PID(kp=1.0, ki=0, kd=0, min_output=0, max_output=1.0, + tolerance=1.0, tolerance_count=3) + # Feed small errors within tolerance (sleep to avoid zero timestep) + for _ in range(5): + pid.update(0.1) + time.sleep(0.002) + assert pid.is_done() + + def test_tolerance_resets_on_large_error(self): + pid = PID(tolerance=0.5, tolerance_count=3) + pid.update(0.1); time.sleep(0.002) + pid.update(0.1); time.sleep(0.002) + pid.update(5.0); time.sleep(0.002) # outside tolerance — resets counter + pid.update(0.1); time.sleep(0.002) + pid.update(0.1) + assert not pid.is_done() # only 2 consecutive, need 3 + + +class TestPIDClearHistory: + def test_clear_resets_state(self): + pid = PID(kp=1.0, ki=1.0, kd=1.0, min_output=0, max_output=100) + for _ in range(5): + pid.update(10.0) + time.sleep(0.01) + pid.clear_history() + assert pid.prev_error == 0 + assert pid.prev_integral == 0 + assert pid.prev_output == 0 + assert pid.prev_time is None + assert pid.times == 0 diff --git a/tests/unit/test_rangefinder.py b/tests/unit/test_rangefinder.py new file mode 100644 index 0000000..b29add7 --- /dev/null +++ b/tests/unit/test_rangefinder.py @@ -0,0 +1,69 @@ +""" +Unit tests for Rangefinder distance calculation math. +""" +import pytest +from XRPLib.rangefinder import Rangefinder + + +class TestRangefinderDistanceCalc: + def test_distance_formula(self): + """Verify the pulse-to-cm conversion math.""" + # Sound speed: 343.2 m/s = 0.03432 cm/us + # Round trip: divide by 2 + # So: distance = pulse_us / 2 / 29.1 + pulse_us = 1164 # ~20cm round trip + expected_cm = pulse_us / 2 / 29.1 + assert expected_cm == pytest.approx(20.0, abs=0.1) + + def test_distance_2cm(self): + pulse_us = 2 * 2 * 29.1 # 2cm * 2 (round trip) * 29.1 + distance = pulse_us / 2 / 29.1 + assert distance == pytest.approx(2.0) + + def test_distance_400cm(self): + pulse_us = 400 * 2 * 29.1 # 400cm + distance = pulse_us / 2 / 29.1 + assert distance == pytest.approx(400.0) + + def test_max_value(self): + assert Rangefinder("RANGE_TRIGGER", "RANGE_ECHO").MAX_VALUE == 65535 + + +class TestRangefinderInstances: + def test_singleton(self): + # Reset class state + Rangefinder._DEFAULT_RANGEFINDER_INSTANCE = None + Rangefinder._instances = [] + Rangefinder._timer = None + Rangefinder._current_index = 0 + + r1 = Rangefinder.get_default_rangefinder() + r2 = Rangefinder.get_default_rangefinder() + assert r1 is r2 + + def test_instance_registered(self): + Rangefinder._instances = [] + Rangefinder._timer = None + Rangefinder._current_index = 0 + + r = Rangefinder("RANGE_TRIGGER", "RANGE_ECHO") + assert r in Rangefinder._instances + + def test_multiple_instances(self): + Rangefinder._instances = [] + Rangefinder._timer = None + Rangefinder._current_index = 0 + + r1 = Rangefinder("RANGE_TRIGGER", "RANGE_ECHO") + r2 = Rangefinder("RANGE_TRIGGER", "RANGE_ECHO") + assert len(Rangefinder._instances) == 2 + + +class TestRangefinderTimeout: + def test_default_timeout(self): + r = Rangefinder("RANGE_TRIGGER", "RANGE_ECHO") + assert r.timeout_us == 500 * 2 * 30 # 30000 us + + def test_custom_timeout(self): + r = Rangefinder("RANGE_TRIGGER", "RANGE_ECHO", timeout_us=50000) + assert r.timeout_us == 50000 diff --git a/tests/unit/test_reflectance.py b/tests/unit/test_reflectance.py new file mode 100644 index 0000000..86c9073 --- /dev/null +++ b/tests/unit/test_reflectance.py @@ -0,0 +1,42 @@ +""" +Unit tests for Reflectance sensor normalization. +""" +import pytest +from XRPLib.reflectance import Reflectance + + +class TestReflectance: + def test_white_surface_low_value(self): + r = Reflectance() + r._leftReflectance._set_value(0) + assert r.get_left() == pytest.approx(0.0) + + def test_dark_surface_high_value(self): + r = Reflectance() + r._leftReflectance._set_value(65535) + result = r.get_left() + # Due to MAX_ADC_VALUE being 65536, this is 65535/65536 + assert result == pytest.approx(1.0, abs=0.001) + + def test_mid_value(self): + r = Reflectance() + r._rightReflectance._set_value(32768) + result = r.get_right() + assert result == pytest.approx(0.5, abs=0.01) + + def test_left_right_independent(self): + r = Reflectance() + r._leftReflectance._set_value(10000) + r._rightReflectance._set_value(50000) + left = r.get_left() + right = r.get_right() + assert left < right + + def test_max_value_not_exactly_one_bug(self): + """Documents the off-by-one: max read (65535) doesn't produce exactly 1.0.""" + r = Reflectance() + r._leftReflectance._set_value(65535) + result = r.get_left() + # This documents the current behavior — not exactly 1.0 + assert result < 1.0 + assert result > 0.999 diff --git a/tests/unit/test_servo.py b/tests/unit/test_servo.py new file mode 100644 index 0000000..b0b4db0 --- /dev/null +++ b/tests/unit/test_servo.py @@ -0,0 +1,46 @@ +""" +Unit tests for Servo angle-to-duty conversion. +""" +import pytest +from XRPLib.servo import Servo + + +class TestServo: + def test_angle_0(self): + s = Servo("SERVO_1") + s.set_angle(0) + # duty_ns = 0 * 10000 + 500000 = 500000 + assert s._servo.duty_ns() == 500000 + + def test_angle_90(self): + s = Servo("SERVO_1") + s.set_angle(90) + # duty_ns = 90 * 10000 + 500000 = 1400000 + assert s._servo.duty_ns() == 1400000 + + def test_angle_180(self): + s = Servo("SERVO_1") + s.set_angle(180) + # duty_ns = 180 * 10000 + 500000 = 2300000 + assert s._servo.duty_ns() == 2300000 + + def test_angle_200_max(self): + s = Servo("SERVO_1") + s.set_angle(200) + # duty_ns = 200 * 10000 + 500000 = 2500000 + assert s._servo.duty_ns() == 2500000 + + def test_free(self): + s = Servo("SERVO_1") + s.set_angle(90) + s.free() + assert s._servo.duty_ns() == 0 + + def test_pwm_frequency(self): + s = Servo("SERVO_1") + assert s._servo.freq() == 50 + + def test_invalid_index_bug(self): + """Documents the same return-Exception bug as EncodedMotor.""" + result = Servo.get_default_servo(99) + assert isinstance(result, Exception) diff --git a/tests/unit/test_timeout.py b/tests/unit/test_timeout.py new file mode 100644 index 0000000..d92d15a --- /dev/null +++ b/tests/unit/test_timeout.py @@ -0,0 +1,33 @@ +""" +Unit tests for Timeout class. +""" +import time +import pytest +from XRPLib.timeout import Timeout + + +class TestTimeout: + def test_not_done_immediately(self): + t = Timeout(1.0) + assert not t.is_done() + + def test_done_after_expiry(self): + t = Timeout(0.05) + time.sleep(0.1) + assert t.is_done() + + def test_none_timeout_never_expires(self): + t = Timeout(None) + assert not t.is_done() + time.sleep(0.05) + assert not t.is_done() + + def test_zero_timeout_expires_immediately(self): + t = Timeout(0) + # A timeout of 0 seconds should expire almost immediately + time.sleep(0.01) + assert t.is_done() + + def test_stores_timeout_in_ms(self): + t = Timeout(2.5) + assert t.timeout == 2500 diff --git a/tests/unit/test_webserver.py b/tests/unit/test_webserver.py new file mode 100644 index 0000000..a77c0ea --- /dev/null +++ b/tests/unit/test_webserver.py @@ -0,0 +1,101 @@ +""" +Unit tests for Webserver HTML generation and button registration. +""" +import pytest +from XRPLib.webserver import Webserver + + +class TestWebserverButtons: + def test_add_button(self): + ws = Webserver() + ws.add_button("test_btn", lambda: None) + assert "test_btn" in ws.buttons + + def test_register_forward_enables_arrows(self): + ws = Webserver() + assert ws.display_arrows is False + ws.registerForwardButton(lambda: None) + assert ws.display_arrows is True + + def test_register_all_arrow_buttons(self): + ws = Webserver() + ws.registerForwardButton(lambda: None) + ws.registerBackwardButton(lambda: None) + ws.registerLeftButton(lambda: None) + ws.registerRightButton(lambda: None) + ws.registerStopButton(lambda: None) + assert ws.display_arrows is True + assert callable(ws.buttons["forwardButton"]) + assert callable(ws.buttons["backButton"]) + assert callable(ws.buttons["leftButton"]) + assert callable(ws.buttons["rightButton"]) + assert callable(ws.buttons["stopButton"]) + + +class TestWebserverHTML: + def test_html_contains_title(self): + ws = Webserver() + html = ws._generateHTML() + assert "XRP control page" in html + + def test_html_contains_custom_button(self): + ws = Webserver() + ws.add_button("my_action", lambda: None) + html = ws._generateHTML() + assert "my_action" in html + + def test_html_excludes_arrow_buttons_from_custom_list(self): + ws = Webserver() + ws.registerForwardButton(lambda: None) + html = ws._generateHTML() + # Arrow buttons should be in the arrow HTML, not duplicated as custom buttons + # Check that forwardButton isn't in a user-button form + assert 'class="user-button" name=forwardButton' not in html + + def test_html_contains_logged_data(self): + ws = Webserver() + ws.log_data("Speed", 42) + html = ws._generateHTML() + assert "Speed" in html + assert "42" in html + + def test_html_arrows_included_when_enabled(self): + ws = Webserver() + ws.registerForwardButton(lambda: None) + html = ws._generateHTML() + assert "↑" in html # up arrow + + def test_html_arrows_excluded_when_disabled(self): + ws = Webserver() + html = ws._generateHTML() + assert "↑" not in html + + +class TestWebserverLogData: + def test_log_data_stores(self): + ws = Webserver() + ws.log_data("distance", 25.3) + assert ws.logged_data["distance"] == 25.3 + + def test_log_data_overwrites(self): + ws = Webserver() + ws.log_data("speed", 10) + ws.log_data("speed", 20) + assert ws.logged_data["speed"] == 20 + + +class TestWebserverFunctionHandler: + def test_handle_valid_function(self): + ws = Webserver() + called = [] + ws.add_button("test", lambda: called.append(True)) + result = ws._handleUserFunctionRequest("test") + assert result is True + assert len(called) == 1 + + def test_handle_invalid_function(self): + ws = Webserver() + # Unknown button name should raise KeyError, caught internally + # but the method catches RuntimeError, not KeyError, so this actually raises + with pytest.raises(KeyError): + ws._handleUserFunctionRequest("nonexistent")