IO Layer Pattern: Hardware Abstraction in Depth
Every subsystem you've built so far talks directly to hardware — TalonFX, CANcoder, Pigeon2. That works on a physical robot. It doesn't work on a laptop, in simulation, or when replaying a match log. The IO layer pattern separates what the subsystem does from which hardware it does it with, unlocking simulation, testing, and replay without changing a line of subsystem logic.
By the end of this lesson, you will:
- Explain the problem that direct hardware coupling creates for simulation and testing
- Define the IO interface for a subsystem, separating inputs (sensor data) from outputs (motor commands)
- Implement three IO classes for the same interface:
RealIO(talks to hardware),SimIO(runs physics model), andReplayIO(replays logged data) - Wire the IO layer into a subsystem so the subsystem only references the interface, never a concrete implementation
- Instantiate the correct IO implementation in
RobotContainerbased on whether the robot is real, simulated, or replaying - Explain why inputs are logged before they are used, and what this enables for deterministic replay
The Problem: Direct Hardware Coupling
In the subsystem pattern you learned in Unit 6, a ShooterSubsystem creates a TalonFX in its constructor and calls m_motor.setControl(...) directly. This is simple and direct, and it works perfectly on the physical robot. The problem surfaces the moment you try to do anything other than running it on a physical robot.
Want to test the shooter's velocity PID loop without a robot? Can't — the TalonFX constructor throws an exception when no CAN bus is present. Want to simulate a match to test your autonomous sequence? Every subsystem that touches hardware fails at construction. Want to replay a match log and see what the robot's subsystems were computing? The hardcoded hardware calls would send real commands to real motors — which isn't what replay means.
The IO layer pattern solves all three of these by inserting an interface between the subsystem's logic and the hardware. The subsystem interacts with an IO interface — something that can provide sensor inputs and receive motor commands. The concrete implementation of that interface (real hardware, simulated physics, or log playback) is decided at startup in RobotContainer and is never changed afterward.
- Subsystem creates
TalonFX,CANcoderetc. directly - Cannot run on a laptop — hardware calls fail
- Cannot simulate without physical robot
- Cannot replay logs without sending real motor commands
- Changing hardware (Phoenix → REV) requires rewriting subsystem logic
- Cannot unit test control logic in isolation
- Subsystem talks to an
IOinterface only - Swap
SimIOin — runs on any laptop - Physics model in
SimIOprovides realistic behavior - Swap
ReplayIOin — subsystem logic runs on logged inputs - Change hardware by swapping only the
RealIOclass - Test control logic against any IO implementation
The Three-File Structure
The IO layer pattern requires three things for each subsystem: an interface that defines the contract, one or more concrete implementations, and a subsystem that works through the interface. Click through the structure in the explorer below to see each component and its role.
Defining the IO Interface
The interface is the contract. It specifies exactly what information the subsystem needs from hardware (inputs) and what commands the subsystem will send to hardware (outputs). The interface contains no implementation — only method signatures and, critically, a nested Inputs class that bundles all sensor readings.
public interface ShooterIO { // ── Inputs: all sensor data the subsystem reads from this mechanism ──────── // This class is a plain data container — no logic, only fields. // It's populated by updateInputs() and passed back to the subsystem. // Making it a nested class keeps all IO types for this subsystem in one file. class ShooterIOInputs { public double velocityRpm = 0.0; public double appliedVolts = 0.0; public double currentAmps = 0.0; public double temperatureCelsius = 0.0; public boolean motorConnected = false; } // ── updateInputs: called once per loop to populate sensor readings ───────── // Each implementation fills the inputs object from its data source: // - RealIO: reads from TalonFX signal API // - SimIO: reads from physics model state // - ReplayIO: reads from the log file // // After updateInputs(), the subsystem logs ALL inputs before using any of them. // This is what enables deterministic replay (Lesson 3). default void updateInputs(ShooterIOInputs inputs) {} // ── Output methods: commands the subsystem sends to the mechanism ────────── default void setVoltage(double volts) {} default void setVelocity(double velocityRpm, double ffVolts) {} default void stop() {} }
default methods so unimplemented IO classes don't require stubsdefault methods on an interface provide a no-op body that is used when an implementation doesn't override the method. For a ReplayIO class, all output methods (setVoltage, setVelocity) should do nothing — you're replaying logged inputs, not sending commands. Rather than requiring every IO class to explicitly implement every method with an empty body, using default void method() {} on the interface means only updateInputs() and the output methods you care about in each implementation need to be written.
The Three IO Implementations
Creates the TalonFX, configures it, reads velocity and current from the Phoenix 6 Signal API, and applies control modes. All hardware-specific code lives here. When the robot's hardware changes (different motor model, encoder type), only this file changes — the subsystem logic is untouched.
Uses WPILib's FlywheelSim to model the shooter's physical behavior. Applies voltage commands to the sim model, steps the physics forward each loop, reads simulated velocity and current. The subsystem's PID loop works against this simulated plant — no hardware needed.
Does nothing in updateInputs() and nothing in output methods. AdvantageKit's replay mechanism overwrites the inputs object directly from the log file before the subsystem's periodic() runs. The subsystem logic re-executes on historical data exactly as it did live.
import com.ctre.phoenix6.hardware.TalonFX; import com.ctre.phoenix6.controls.*; public class ShooterIOTalonFX implements ShooterIO { private final TalonFX m_motor = new TalonFX(11); private final VelocityVoltage m_velocityCtrl = new VelocityVoltage(0); private final VoltageOut m_voltageCtrl = new VoltageOut(0); public ShooterIOTalonFX() { // Configure motor — current limits, sensor source, direction var config = new TalonFXConfiguration(); config.CurrentLimits.SupplyCurrentLimit = 40; config.CurrentLimits.SupplyCurrentLimitEnable = true; m_motor.getConfigurator().apply(config); } @Override public void updateInputs(ShooterIOInputs inputs) { // Read fresh sensor data from TalonFX signals // Phoenix 6 signals are cached — reading them here is cheap inputs.velocityRpm = m_motor.getVelocity().getValueAsDouble() * 60; inputs.appliedVolts = m_motor.getMotorVoltage().getValueAsDouble(); inputs.currentAmps = m_motor.getSupplyCurrent().getValueAsDouble(); inputs.temperatureCelsius = m_motor.getDeviceTemp().getValueAsDouble(); inputs.motorConnected = m_motor.isAlive(); } @Override public void setVelocity(double velocityRpm, double ffVolts) { m_motor.setControl(m_velocityCtrl .withVelocity(velocityRpm / 60.0) .withFeedForward(ffVolts)); } @Override public void setVoltage(double volts) { m_motor.setControl(m_voltageCtrl.withOutput(volts)); } @Override public void stop() { m_motor.stopMotor(); } }
import edu.wpi.first.math.system.plant.DCMotor; import edu.wpi.first.wpilibj.simulation.FlywheelSim; public class ShooterIOSim implements ShooterIO { // FlywheelSim models the physics of a spinning flywheel: // motor type, gear ratio, moment of inertia (kg·m²) // Higher MOI = spins up and down more slowly (more flywheel mass) private final FlywheelSim m_sim = new FlywheelSim( DCMotor.getKrakenX60(1), // motor model 1.5, // gear ratio (motor : flywheel) 0.004 // flywheel MOI (kg·m²) — tune to match real spin-up time ); private double m_appliedVolts = 0.0; @Override public void updateInputs(ShooterIOInputs inputs) { // Step the physics simulation forward by one 20ms loop m_sim.setInputVoltage(m_appliedVolts); m_sim.update(0.020); // Populate inputs from simulated state inputs.velocityRpm = m_sim.getAngularVelocityRPM(); inputs.appliedVolts = m_appliedVolts; inputs.currentAmps = m_sim.getCurrentDrawAmps(); inputs.motorConnected = true; // always "connected" in sim } @Override public void setVoltage(double volts) { // Clamp to ±12V (battery limit) m_appliedVolts = MathUtil.clamp(volts, -12.0, 12.0); } @Override public void setVelocity(double velocityRpm, double ffVolts) { // For closed-loop sim, apply the feedforward voltage directly. // The subsystem's PID controller adds correction on top of this. m_appliedVolts = MathUtil.clamp(ffVolts, -12.0, 12.0); } @Override public void stop() { m_appliedVolts = 0.0; } }
The Subsystem: Pure Logic, No Hardware
The subsystem holds an IO reference, calls updateInputs() at the start of each periodic(), logs the inputs (essential for AdvantageKit replay, covered in Lesson 3), and then runs all its control logic using those input values. It never calls hardware directly.
public class Shooter extends SubsystemBase { private final ShooterIO m_io; private final ShooterIOInputs m_inputs = new ShooterIOInputs(); private final PIDController m_pid = new PIDController(0.0001, 0, 0); private final SimpleMotorFeedforward m_ff = new SimpleMotorFeedforward(0.1, 0.0025); private double m_targetRpm = 0.0; // Constructor takes the IO interface — subsystem doesn't care which implementation public Shooter(ShooterIO io) { m_io = io; } @Override public void periodic() { // Step 1: Update inputs from IO (hardware, sim, or log) // This MUST happen first, before any logic reads m_inputs. m_io.updateInputs(m_inputs); // Step 2: Log ALL inputs to AdvantageKit (before any reads). // Logger.processInputs() is what enables deterministic replay. // Covered in depth in Lesson 2 (AdvantageKit intro). Logger.processInputs("Shooter", m_inputs); // Step 3: Run control logic using inputs — same code for real/sim/replay if (m_targetRpm > 0) { double ffVolts = m_ff.calculate(m_targetRpm); double pidVolts = m_pid.calculate(m_inputs.velocityRpm, m_targetRpm); m_io.setVelocity(m_targetRpm, ffVolts + pidVolts); } // Log outputs for debugging (covered in Lesson 2) Logger.recordOutput("Shooter/TargetRpm", m_targetRpm); Logger.recordOutput("Shooter/ActualRpm", m_inputs.velocityRpm); Logger.recordOutput("Shooter/AtSpeed", isAtTargetSpeed()); } public void setTargetRpm(double rpm) { m_targetRpm = rpm; } public void stop() { m_targetRpm = 0; m_io.stop(); } public boolean isAtTargetSpeed() { return Math.abs(m_inputs.velocityRpm - m_targetRpm) < 50; } public double getVelocityRpm() { return m_inputs.velocityRpm; } }
Wiring the Right Implementation in RobotContainer
The only place in the entire codebase where a concrete IO implementation is chosen is RobotContainer's constructor. The decision is made once at startup based on runtime conditions — whether the code is running on a real robot, in simulation, or in replay mode.
import edu.wpi.first.wpilibj.RobotBase; public class RobotContainer { private final Shooter m_shooter; public RobotContainer() { if (RobotBase.isReal()) { // Running on physical robot hardware m_shooter = new Shooter(new ShooterIOTalonFX()); } else if (Constants.isReplay) { // Replaying a previously recorded match log (AdvantageKit replay) // ShooterIOReplay has empty updateInputs() — AdvantageKit overwrites // m_inputs directly from the log before periodic() runs. m_shooter = new Shooter(new ShooterIOReplay()); } else { // Running in simulation on a laptop (no hardware) m_shooter = new Shooter(new ShooterIOSim()); } configureBindings(); } }
After the constructor finishes, Shooter holds an m_io reference of type ShooterIO — the interface. It cannot know, and does not care, whether this is a TalonFX, a simulated flywheel, or a log replayer. This is the core of the pattern. The subsystem's PID loop, feedforward calculations, speed-check methods, and state management run identically in all three cases. The only thing that changes between real, sim, and replay is what updateInputs() does and what setVelocity() does — and those details are encapsulated behind the interface.
Why Inputs Must Be Logged Before They Are Used
There is a strict order requirement in the subsystem's periodic(): updateInputs() → Logger.processInputs() → use inputs in logic. Violating this order breaks AdvantageKit's replay capability.
Here's why: during replay mode, Logger.processInputs() is not just a logging call — it also overwrites the inputs object with values from the log file. The log contains the exact sensor readings from every loop during the original match. When the replay runner calls periodic(), it first loads the historically correct inputs into m_inputs, then the subsystem logic runs on those historical values. The subsystem computes exactly what it would have computed during the match. This is deterministic replay.
If you read from m_inputs before calling Logger.processInputs(), you read the inputs from updateInputs() (which in replay mode does nothing) — your logic runs on all-zero inputs instead of the historical data. The replay produces wrong results. The fix is simple: processInputs() always immediately after updateInputs(), before a single m_inputs.field is read.
Teams 6328 (AdvantageKit authors), 2910, and 971 build the IO layer pattern into every subsystem from week one of build season. The reason is pragmatic: retrofitting it onto existing subsystems mid-season is painful and error-prone. Starting with the pattern means simulation and replay work from day one, autonomous routines can be developed without a robot, and every match log is a debugging artifact that can be replayed exactly. The teams that add it late in the season often do so after a frustrating competition where they couldn't diagnose a failure because they had no way to replay the match state. The pattern's cost is 20–30 minutes of extra structure per subsystem. Its return is the entire debugging infrastructure of Unit 11, Lessons 2–6.
🔌 System Check
After implementing the IO layer for a subsystem, verify each of these:
- The subsystem compiles and runs in simulation (
RobotBase.isSimulation()= true). Deploy to simulation and confirm the subsystem starts without throwing any hardware exceptions. If you see a CAN bus error or device constructor exception, a concrete hardware class is still being instantiated when it shouldn't be — check the RobotContainer conditional. - The subsystem's inputs appear in SmartDashboard / AdvantageKit when running on the real robot. After
Logger.processInputs()is called, the subsystem's inputs should be logged. Open SmartDashboard or AdvantageScope and confirmShooter/velocityRpm,Shooter/currentAmps, etc. appear. If they don't, verifyLogger.processInputs("Shooter", m_inputs)is being called correctly. - The
isAtTargetSpeed()method returns a correct result in both simulation and on the real robot. Command the shooter to a target RPM. In both simulation and reality,isAtTargetSpeed()should return true when the velocity is within tolerance. If it's always false, verify the inputs are being populated (check the SmartDashboard values above). - Only
RobotContainercontains references toShooterIOTalonFX,ShooterIOSim, orShooterIOReplay. Search your codebase for these class names. The only file that should import them isRobotContainer.java. If any other file imports a concrete IO class, the abstraction is broken.
Knowledge Check
1. A team's Shooter.java subsystem imports and directly instantiates TalonFX in its constructor. The subsystem works perfectly on the robot. When they try to run in simulation to test the auto routine, the subsystem crashes with a CAN device exception. What architectural change is necessary to fix this for all future subsystems, and what does it enable beyond just fixing the crash?
2. In the IO pattern, a programmer writes the following in periodic(): if (m_inputs.velocityRpm > 3000) doSomething(); m_io.updateInputs(m_inputs); Logger.processInputs("Shooter", m_inputs);. The code works on the robot. What breaks in AdvantageKit replay mode, and why?
3. A team decides to switch their shooter motor from TalonFX to a REV SparkFlex mid-season. With the IO layer pattern fully implemented, which files must change, and which must not?
Refactor One Subsystem to Use the IO Layer Pattern
- Choose a mechanism subsystem from your existing robot code that directly instantiates hardware (a motor controller, encoder, or pneumatic). Write the
IOinterface for it: a nestedInputsclass with all sensor fields, anupdateInputs()method signature, and output method signatures (setVoltage(),setPosition(), etc.). Usedefaultmethods with empty bodies for all methods. - Implement
RealIO: move all hardware construction and configuration from the original subsystem into this class. ImplementupdateInputs()to populate inputs from the hardware's signals. Implement each output method to send commands to the hardware. The original subsystem should no longer import any hardware classes after this step. - Implement
SimIO: use the appropriate WPILib simulation class (FlywheelSim,ElevatorSim,SingleJointedArmSim, orDCMotorSim) to model the mechanism's physics. ImplementupdateInputs()to step the sim and read its state. Implement output methods to apply commands to the sim. - Refactor the subsystem to accept the interface in its constructor. Update
periodic()to callupdateInputs()then immediatelyLogger.processInputs()(or at minimumSmartDashboard.putNumber()for each input field) before any logic reads fromm_inputs. Confirm the subsystem has no direct hardware imports. - Bonus: Run the code in simulation (
./gradlew simulateJava). Confirm the subsystem initializes without hardware exceptions. Command the mechanism to a target position or speed using a test command. Observe the simulated response in SmartDashboard — does the mechanism reach its target? Does the response time seem physically plausible? If the sim spins up instantly or never spins up, adjust theSimIO's MOI or gear ratio.