Skip to main content

AdvantageKit and IO Layers


When working with code in general, it is often necessary to review how the system behaved in the past to diagnose issues or confirm correct behavior. Traditional robot logging systems typically record only a limited set of values predetermined in advance. AdvantageKit takes this further by recording all of the data flowing into the robot code. Every loop cycle, it logs sensor readings, controller inputs, button presses, and more.

After a match, this data can be replayed in a simulator, feeding the exact same inputs back into the robot code. Because the inputs are identical, the robot's internal logic runs exactly as it did on the field. This means developers can:

  • Add new logging fields after the fact and still see accurate results.
  • Modify processing pipelines and test how they would have worked during the match.
  • Debug and validate any part of the code, not just the sections that were pre-selected for logging.

IO Layers

In robot code, IO layers (Input/Output layers) are the parts of the program that connect your high-level robot logic to the actual hardware. Instead of having subsystems talk directly to motors, sensors, and controllers, they talk to an IO layer. The IO layer then handles all the “real world” details of sending commands to motors or reading values from sensors. AdvantageKit depends on IO Layers to function.

Think of it like this:

  • Subsystems decide what the robot should do (e.g., “spin the shooter at 3000 RPM”).
  • IO layers handle how that command is carried out (e.g., “tell the Spark Max motor controller to set velocity to 3000 RPM”).

Usefulness

Imagine we are in the middle of the Lehigh District Championship Event and we have an important match. Our robot contains an elevator run by 2 Kraken X60s, and suddenly, the internal gearbox of the Kraken breaks. Yikes! Now, you must rely on NEOs, so the Mechanical subteam makes the necessary adjustments. However, both of these motors use vastly different motor controllers, so when you test the robot, nothing happens. You end up being unable to fix the problem in time, are unable to score the entire match, and end up losing. All of this could have been avoided if you wrote one small class.

Hardware Abstraction

Think of the IO layer as a “translator.” Subsystems never talk directly to hardware; they only talk to the IO layer. The IO layer then decides how to communicate with the specific motor or sensor.

  • Example: The Shooter subsystem doesn’t care if it uses a Spark Max, TalonFX, or even a simulated motor. It just says, “spin at 3000 RPM.”
    If the team changes hardware later, we don’t touch the subsystem code; we only rewrite the IO layer. If this IO Layer is already written, you simply need to swap it with the current one for the code to perform as originally intended.

Simulation and Replay

One of AdvantageKit’s strongest features is testing without a robot. IO layers make this possible.

  • Real IO talks to actual hardware when the robot is on the field.
  • Sim IO fakes the hardware so we can run robot code in simulation.
  • Replay IO uses recorded logs to “replay” a past match or practice run. By swapping IO implementations, the same subsystem code works everywhere. This makes it easier to test code and debug, even when the robot isn’t ready for testing.

AdvantageKit automatically logs both inputs (like sensor values) and outputs (like motor commands). The IO layer is where this logging happens.

Because every piece of data goes through the IO layer, we get a complete record of what the robot was doing during a match. Later, we can open the logs, see exactly what commands were sent, and compare them to what the sensors reported. This makes debugging and tuning far easier than guessing.

Example

Below is an example of a sample IO layer for the NavX in AdvantageKit

package frc.robot.subsystems.drive;

import com.kauailabs.navx.frc.AHRS;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.SPI;
import java.util.OptionalDouble;
import java.util.Queue;
import org.littletonrobotics.junction.Logger;

/** IO implementation for NavX */
public class GyroIONavX implements GyroIO {
byte updateRate = 50;
private final AHRS navx = new AHRS(SPI.Port.kMXP);
private final Queue<Double> yawPositionQueue;
private final Queue<Double> yawTimestampQueue;

public GyroIONavX() {
if (!navx.isCalibrating()) {
navx.reset();
} else {
// Wait for calibration to finish, then reset
new Thread(
() -> {
try {
// 1 second calibration time after factory calibration
Thread.sleep((1000));
navx.reset();
} catch (Exception e) {
}
})
.start();
}
yawTimestampQueue = SparkMaxOdometryThread.getInstance().makeTimestampQueue();
yawPositionQueue =
SparkMaxOdometryThread.getInstance()
.registerSignal(
() -> {
boolean valid = navx.isConnected();
if (valid) {
return OptionalDouble.of(-navx.getFusedHeading());
} else {
return OptionalDouble.empty();
}
});
}

@Override
public void updateInputs(GyroIOInputs inputs) {
inputs.connected = navx.isConnected();
inputs.yawPosition = Rotation2d.fromDegrees(-navx.getFusedHeading());
inputs.yawVelocityRadPerSec = Units.degreesToRadians(-navx.getRate());
inputs.odometryYawTimestamps =
yawTimestampQueue.stream().mapToDouble((Double value) -> value).toArray();
inputs.odometryYawPositions =
yawPositionQueue.stream()
.map((Double value) -> Rotation2d.fromDegrees(value))
.toArray(Rotation2d[]::new);
yawTimestampQueue.clear();
yawPositionQueue.clear();

Logger.recordOutput("Gyro/fusedHeading", navx.getFusedHeading());
Logger.recordOutput("Gyro/compassHeading", navx.getCompassHeading());
Logger.recordOutput("Gyro/compassX", navx.getRawMagX());
Logger.recordOutput("Gyro/compassY", navx.getRawMagY());
Logger.recordOutput("Gyro/compassZ", navx.getRawMagZ());
Logger.recordOutput("Gyro/accelX", navx.getRawAccelX());
Logger.recordOutput("Gyro/accelY", navx.getRawAccelY());
Logger.recordOutput("Gyro/accelZ", navx.getRawAccelZ());
}

@Override
public void resetGyro() {
navx.reset();
}
}

An inputs layer must be predefined where all of the data you want to read from the hardware is declared. The updateInputs() method is called periodically and will update the values into the inputs to be used elsewhere.

Ensure to also record all data you wish to visualize for later using the AdvantageKit logger in order to keep track and replay the data.