diff --git a/training/modules/yagsl.md b/training/modules/yagsl.md
new file mode 100644
index 0000000..57d735d
--- /dev/null
+++ b/training/modules/yagsl.md
@@ -0,0 +1,354 @@
+---
+type: training-material
+domain: programming
+subdomain: swerve-drive
+level: 2
+tags: [yagsl, swerve, drivetrain, java, can, encoder, gyro, pid, autonomous]
+prerequisites: [programming-level-1, electrical-level-1]
+related: [swere-training-hub, photonvision, systemcore]
+source: https://docs.yagsl.com/
+last_verified: 2026-05-15
+freshness: seasonal
+status: active
+growth: tree
+---
+
+# YAGSL — Yet Another Generic Swerve Library
+
+**Website:**
+**GitHub:**
+**Current Version:** 2025.8.0
+**Team 2890 Usage:** Primary swerve drive library on Mothman
+
+## What It Is
+
+YAGSL (Yet Another Generic Swerve Library) is an open-source FRC library that lets you configure an entire swerve drivetrain through JSON files instead of writing custom Java code for each module. You describe your hardware in a few config files, and YAGSL generates the `SwerveDrive` object that handles kinematics, odometry, path following, and more.
+
+The core idea: **one line of Java, a directory of JSON, and you have a working swerve drive.**
+
+## Why We Use It
+
+Team 2890 runs YAGSL on Mothman with SDS MK4i modules, NEO Vortex drive motors, SPARK Flex controllers, and CANcoders. YAGSL lets us swap hardware (different motors, different encoders, different gyros) by editing JSON instead of rewriting Java code.
+
+**Advantages over rolling your own swerve code:**
+- JSON config means hardware changes are data, not code changes
+- Built-in support for PathPlanner autonomous integration
+- Vision odometry integration (works with PhotonVision out of the box)
+- Simulation support for testing without a robot
+- Active community and frequent updates
+
+## Hardware That YAGSL Supports
+
+### Motor Controllers
+- SPARK MAX / SPARK Flex (REV)
+- Talon SRX / FX / FXv2 (CTRE)
+- Victorian / Jaguar (legacy)
+
+### Absolute Encoders
+- CANcoder (CTRE)
+- CANandmag (Redux)
+- SparkMaxAnalog / SparkMaxAlternate / SparkMaxAttached (REV)
+
+### Gyroscopes (IMU)
+- Pigeon 2 (CTRE)
+- NavX2 / NavX (Studica / Kauai Labs)
+- ADIS16448 / ADIS16470 / ADXRS450 (Analog Devices)
+- ADXL345 (WPILib built-in)
+
+### Supported Motors
+- NEO / NEO Vortex / NEO 550 (REV)
+- Falcon 500 / Falcon 500 (v6) / Kraken X60 (CTRE)
+- Brushed motors with external encoders (SparkMAX only)
+
+## JSON Configuration Structure
+
+YAGSL reads configuration from the `deploy/swerve/` directory in your WPILib project:
+
+```
+src/main/deploy/swerve/
+ swervedrive.json <- Main config (IMU, module list)
+ frontleft.json <- Module 1
+ frontright.json <- Module 2
+ backleft.json <- Module 3
+ backright.json <- Module 4
+```
+
+### swervedrive.json (Main Config)
+
+```json
+{
+ "imu": {
+ "type": "pigeon2",
+ "id": 13,
+ "canbus": "canivore"
+ },
+ "invertedIMU": true,
+ "modules": [
+ "frontleft.json",
+ "frontright.json",
+ "backleft.json",
+ "backright.json"
+ ]
+}
+```
+
+Key fields:
+- `imu.type` — Your gyro model (pigeon2, navX, etc.)
+- `imu.id` — CAN device ID
+- `imu.canbus` — CAN bus name ("canivore" or null for rio bus)
+- `invertedIMU` — Flip the gyro heading if your IMU is mounted upside down
+- `modules` — List of module config files, clockwise from front-left
+
+### Module JSON (e.g., frontleft.json)
+
+```json
+{
+ "drive": {
+ "type": "sparkflex",
+ "id": 2,
+ "canbus": null
+ },
+ "angle": {
+ "type": "sparkflex",
+ "id": 1,
+ "canbus": null
+ },
+ "encoder": {
+ "type": "cancoder",
+ "id": 10,
+ "canbus": null
+ },
+ "inverted": {
+ "drive": false,
+ "angle": false
+ },
+ "absoluteEncoderInverted": false,
+ "absoluteEncoderOffset": -50.977,
+ "location": {
+ "front": 12,
+ "left": -12
+ }
+}
+```
+
+Key fields:
+- `drive` / `angle` — Motor controller type and CAN ID
+- `encoder` — Absolute encoder type and CAN ID
+- `inverted` — Motor direction inversion (separate for drive and angle)
+- `absoluteEncoderOffset` — CRITICAL: the angular offset to align the wheel forward (see below)
+- `location` — Physical position of the module relative to robot center (inches)
+
+## The Eight Steps of Bringing Up Swerve
+
+YAGSL's docs recommend a specific order for first-time configuration. Follow these in sequence — do not skip steps:
+
+1. **Install dependencies** — All vendor libraries (CTRE, REV, etc.)
+2. **Check your gyroscope** — Verify it reads heading correctly
+3. **Check your motors** — Verify CAN IDs and direction
+4. **Create your configuration** — JSON files with correct device IDs
+5. **Verify module locations** — Physical position matches config
+6. **Tune drive PID** — Drive motor velocity PID
+7. **Tune angle PID** — Steering motor angle PID
+8. **Verify odometry** — Robot position tracks correctly
+
+**Common mistake:** Trying to tune PID before verifying CAN IDs. Every wrong CAN ID causes cascading failures that look like PID problems but are actually configuration problems.
+
+## Code Setup
+
+### Dependency Installation (vendordep URLs for 2026)
+
+Install these via WPILib's "Install vendor libraries" in VS Code:
+
+- **YAGSL**: `https://broncbotz3481.github.io/YAGSL-Lib/yagsl/yagsl.json`
+- **CTRE Phoenix 6**: `https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-replay-frc2026-latest.json`
+- **CTRE Phoenix 5**: `https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix5-replay-frc2026-latest.json`
+- **REVLib**: `https://software-metadata.revrobotics.com/REVLib-2026.json`
+- **Studica (NavX)**: `https://dev.studica.com/maven/release/2026/json/Studica-2026.0.0.json`
+- **MapleSim**: `https://shenzhen-robotics-alliance.github.io/maple-sim/vendordep/maple-sim.json`
+
+**Important:** You MUST install ALL vendor dependencies even if you only use some of the devices. YAGSL is generic and compiles against all of them.
+
+### Minimal Subsystem
+
+```java
+import edu.wpi.first.wpilibj.Files;
+import edu.wpi.first.wpilibj2.command.SubsystemBase;
+import swervelib.SwerveDrive;
+
+import java.io.File;
+
+public class SwerveSubsystem extends SubsystemBase {
+ private final SwerveDrive swerveDrive;
+
+ public SwerveSubsystem() {
+ swerveDrive = new SwerveDrive(
+ new File(Filesystem.getDeployDirectory(), "swerve")
+ );
+ }
+
+ public SwerveDrive getSwerveDrive() {
+ return swerveDrive;
+ }
+}
+```
+
+That's it. The JSON config files do the heavy lifting.
+
+### Driving the Robot
+
+```java
+// In your RobotContainer:
+new Joystick(driverJoystick, 0); // Xbox or flight stick
+
+// Map joystick axes to drive commands:
+swerveSubsystem.setDefaultCommand(
+ new RunCommand(
+ () -> swerveDrive.drive(
+ // X, Y, rotation — WPILib ChassisSpeeds or raw values
+ joystick.getLeftY(), // Forward/back
+ joystick.getLeftX(), // Left/right
+ joystick.getRightX(), // Rotation
+ true // Field-relative?
+ ),
+ swerveSubsystem
+ )
+);
+```
+
+## Encoder Offsets — The Most Important Number
+
+The `absoluteEncoderOffset` in each module JSON is the single most critical configuration value. It tells the steering motor where "forward" is for that wheel.
+
+### How to Find Your Offset
+
+1. **Align all wheels physically forward** — Point every wheel straight ahead
+2. **Read the raw encoder value** from SmartDashboard or ShuffleBoard
+3. **Negate that value** — That's your offset
+4. **Put it in the module JSON** as `absoluteEncoderOffset`
+
+Example: If the raw encoder reads `149.06`, the offset is `-149.06`.
+
+**Pitfall:** Offsets change if you physically move the encoder gear or swap modules. Re-verify after any hardware change.
+
+**2026 Note:** The `pushOffsetsToEncoders` and `restoreInternalOffset` methods are deprecated in YAGSL 2026+. Offsets should be set in the JSON config and left alone.
+
+## PID Tuning
+
+YAGSL has two PID loops per module: one for drive velocity, one for steering angle.
+
+### Angle (Steering) PID
+- Start with just P gain
+- The steering motor wraps at 180°/-180°, so test with lateral (left/right) translation, not just forward
+- Typical starting P: 0.5-2.0 depending on module
+- If the wheel oscillates around target, P is too high
+- Add D if the wheel overshoots and rings
+
+### Drive PID
+- Tune for velocity, not position
+- Start with just P (try 0.1)
+- Use ShuffleBoard or FRC Web Components to see actual vs commanded velocity
+- Feedforward is important here — YAGSL supports kS, kV, kA
+
+**Test order:** Always tune angle PID before drive PID. A mis-steered module gives garbage drive data.
+
+## Inversion — When to Invert
+
+The most common YAGSL problem is wrong motor inversion. The docs have a dedicated flowchart (see "When to Invert?"), but the rules are:
+
+- `drive` inversion: Flip if the wheel spins backward when commanded forward
+- `angle` inversion: Flip if the steering turns the wrong direction
+- `absoluteEncoderInverted`: Flip if the encoder reads backwards
+- `invertedIMU`: Flip if the gyro reads heading opposite to expected
+
+**Test method:** Drive forward with ShuffleBoard open. If any wheel spins backward, flip its drive inversion. If any wheel turns the wrong way, flip its angle inversion.
+
+## PathPlanner Integration
+
+YAGSL integrates with PathPlanner for autonomous path following:
+
+```java
+// Create auto builder from SwerveDrive
+AutoBuilder.configure(
+ swerveDrive::getPose, // Robot pose supplier
+ swerveDrive::resetOdometry, // Reset pose
+ swerveDrive::getRobotVelocity, // Robot velocity
+ swerveDrive::drive, // Drive consumption
+ new PPHolonomicDriveController( // Holonomic path follower
+ new PIDConstants(5.0, 0.0, 0.0), // Translation PID
+ new PIDConstants(5.0, 0.0, 0.0) // Rotation PID
+ ),
+ swerveDrive.getSwerveDriveConfiguration(), // Config
+ () -> { /* alliance supplier */ },
+ this // Subsystem
+);
+```
+
+## Vision Odometry
+
+YAGSL can fuse vision measurements into odometry. This is how PhotonVision AprilTag data improves your robot's field position:
+
+```java
+// Add a vision measurement (from PhotonVision, Limelight, etc.)
+swerveDrive.addVisionMeasurement(
+ new Pose2d(3, 3, Rotation2d.fromDegrees(65)),
+ Timer.getFPGATimestamp()
+);
+```
+
+See [[photonvision]] for the full AprilTag pipeline.
+
+## Debugging Tools
+
+- **FRC Web Components** — Real-time swerve visualization widget. Connects to SmartDashboard/swerve. Blue lines = measured, shows each module's velocity and position
+- **AdvantageScope** — Log viewer and swerve visualization
+- **YAGSL Config Generator** — includes example configs for common hardware combos
+- **ShuffleBoard** — Standard WPILib dashboard, shows raw encoder values
+
+## Common Problems
+
+| Problem | Likely Cause | Fix |
+|----------|-------------|-----|
+| Wheel spins backward | `inverted.drive` is wrong | Flip the boolean |
+| Wheel steers wrong direction | `inverted.angle` is wrong | Flip the boolean |
+| Robot drifts while driving straight | Encoder offset wrong, or angle PID not tuned | Re-verify offsets, then tune angle PID |
+| Robot won't go straight on its own | No heading correction enabled | Use `swerveDrive.setHeadingCorrection(true)` |
+| "Invalid year" vendordep error | YAGSL JSON has wrong FRC year | Update vendordep URL to current year |
+| Modules don't align on startup | Offset not set or wrong CAN ID | Verify offsets and CAN IDs |
+| Odometry doesn't match field | Module physical positions in JSON are wrong | Re-measure and update `location` fields |
+
+## 2026 Migration Notes
+
+- `pushOffsetsToEncoders` and `restoreInternalOffset` are deprecated — set offsets in JSON only
+- YAGSL vendordep year must match WPILib year (2025 JSON → 2026 build = error)
+- Update all vendor dependencies to 2026 versions simultaneously
+- Check the Chief Delphi thread for YAGSL 2026 plans and ongoing beta testing
+
+## Practice Exercises
+
+### Level 1 — Configuration
+1. Create a minimal YAGSL project from the example repo
+2. Identify every CAN device on your robot and write down the IDs
+3. Fill in the `swervedrive.json` and module JSON files with your hardware
+
+### Level 2 — Bring-Up
+4. Verify each motor responds to the correct CAN ID (use ShuffleBoard)
+5. Find encoder offsets for all four modules
+6. Tune angle PID until all four modules hold their target position
+7. Drive the robot in teleop and verify field-relative control
+
+### Level 3 — Advanced
+8. Set up PathPlanner with a simple auto path
+9. Add PhotonVision AprilTag pose estimation to YAGSL odometry
+10. Configure simulation and test autonomous paths in sim
+
+## Resources
+
+- **Official Docs:**
+- **YAGSL Example Project:**
+- **Chief Delphi Discussion:**
+- **SDS MK4i Documentation:**
+- **Team 2890 Swerve Hub:** [[swere-training-hub]]
+
+---
+
+*Module maintained by 2890-claw. Last verified 2026-05-15 against YAGSL 2025.8.0 docs.*
\ No newline at end of file
diff --git a/training/requests/20260515-yagsl-update.md b/training/requests/20260515-yagsl-update.md
index b7473e0..426eb64 100644
--- a/training/requests/20260515-yagsl-update.md
+++ b/training/requests/20260515-yagsl-update.md
@@ -2,10 +2,12 @@
type: update-request
software: "YAGSL"
old_version: "2025.0.14"
-new_version: "unknown"
+new_version: "2025.8.0"
date: 20260515
-status: pending
+status: fulfilled
priority: high
+fulfilled_date: 2026-05-15
+fulfilled_module: training/modules/yagsl.md
---
# Update Request: YAGSL
@@ -13,17 +15,18 @@ priority: high
New version or content change detected.
- **Previous version:** 2025.0.14
-- **New version:** unknown
-- **Change:** No wiki module exists yet — create one
+- **New version:** 2025.8.0
+- **Change:** No wiki module existed — created one
- **Source:** https://github.com/BroncBotz3481/YAGSL/releases
## Wiki Module
-No wiki module exists yet — create one
+Created: `training/modules/yagsl.md`
+
+- Full training module covering YAGSL fundamentals, JSON configuration, encoder offsets, PID tuning, PathPlanner integration, vision odometry, debugging tools, and 2026 migration notes
+- Includes three levels of practice exercises (Configuration, Bring-Up, Advanced)
+- Cross-linked to swerve training hub, photonvision, and systemcore modules
## Instructions for Claw
-1. Check the release notes/changelog at the source URL
-2. Update the wiki module with new features, API changes, or breaking changes
-3. If this is a major version bump, ensure prerequisites are still accurate
-4. Mark this request as fulfilled in frontmatter when done
+FULFILLED — module created and update-tracker.yaml updated.
diff --git a/training/update-tracker.yaml b/training/update-tracker.yaml
index 2246ead..1ffc12d 100644
--- a/training/update-tracker.yaml
+++ b/training/update-tracker.yaml
@@ -29,12 +29,12 @@ tracked_software:
- name: YAGSL
source_url: https://docs.yagsl.com/
release_url: https://github.com/BroncBotz3481/YAGSL/releases
- current_version: 2025.0.14
- wiki_module: null
+ current_version: 2025.8.0
+ wiki_module: yagsl
check_frequency: on-season:daily,off-season:weekly
last_checked: '2026-05-15'
- last_updated: null
- notes: Swerve drive library. 2890 uses this.
+ last_updated: '2026-05-15'
+ notes: Swerve drive library. 2890 uses this. Module created 2026-05-15.
- name: FRC Game Manual
source_url: https://firstfrc.blob.core.windows.net/frc2024/Manual/2024FRCGameManual.pdf
release_url: https://www.firstinspires.org/resource-library/frc/game-and-season-info