This week, we dive into advanced topics that are crucial for building robust, maintainable, and testable robot code. We'll start with the fundamentals of how the roboRIO communicates with hardware, then introduce AdvantageKit, a powerful library for logging, simulation, and hardware abstraction.
Understand the different hardware communication protocols (DIO, PWM, CAN).
Learn how to interact with common FRC hardware like motors, encoders, gyros, and solenoids using WPILib.
Understand the purpose of AdvantageKit and its IO Layer architecture.
Learn how to create an IO interface and implementations for real and simulated hardware.
Structure a subsystem to use an IO layer for hardware abstraction.
Use AdvantageKit's Logger to log inputs and outputs for debugging and replay.
Before we can build complex systems, we need to understand how to talk to individual devices.
DIO (Digital Input/Output): Communicates with simple on/off signals. Used for limit switches, buttons, and some sensors.
PWM (Pulse Width Modulation): Controls device speed by varying an electrical pulse's width. Used for simple motors, servos, and some encoders.
CAN (Controller Area Network): A more advanced network bus that allows multiple devices to communicate. Each device has a unique ID. This is the standard for modern FRC motors and many sensors.
Digital Inputs (DI)
The most basic input is a simple on/off signal.
import edu.wpi.first.wpilibj.DigitalInput;
DigitalInput limitSwitch = new DigitalInput(0); // Connected to DIO port 0
boolean isPressed = limitSwitch.get();
Encoders
Encoders measure shaft rotation, which gives us distance, velocity, and angle. While some connect to DIO ports, the ones we use most are integrated into our motors and communicate over CAN.
Name
Type
Description
NEO Encoder
Relative
Integrated into REV NEO motors. Communicates over CAN via a SparkMax.
REV Through Bore Encoder
Absolute
Placed around a mechanism's output shaft.
Kraken / Falcon Encoder
Relative
Integrated into CTRE Kraken and Falcon motors. Communicates over CAN.
CTRE CANcoder
Absolute
Uses a magnet inside a shaft to read absolute position. Communicates over CAN.
The NEO Encoder is the one you'll use most. You access it through its parent CANSparkMax motor controller.
import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkMaxLowLevel.MotorType;
import com.revrobotics.RelativeEncoder;
CANSparkMax neoMotor = new CANSparkMax(0, MotorType.kBrushless);
RelativeEncoder encoder = neoMotor.getEncoder();
// Get position in rotations
double position = encoder.getPosition();
// Get velocity in RPM
double velocity = encoder.getVelocity();
NEO encoders are relative: they measure rotation from when they were last powered on or reset.
Conversion Factors
By default, NEO encoders report rotations and RPM. To convert this to useful units like meters or degrees, we set conversion factors. The formula is output = rotor_rotations * conversionFactor. This means the factor should usually be 1.0 / gearRatio.
// Example for drivetrain: meters per wheel rotation, then per motor rotation
double wheelDiameterMeters = 0.1524; // 6 inches
double wheelCircumferenceMeters = Math.PI * wheelDiameterMeters;
double gearRatio = 10.0; // motor rotations per wheel rotation
encoder.setPositionConversionFactor(wheelCircumferenceMeters / gearRatio); // meters
encoder.setVelocityConversionFactor((wheelCircumferenceMeters / gearRatio) / 60.0); // m/s (RPM -> RPS -> m/s)
Gyroscopes
A gyroscope measures orientation (angle/heading). We commonly use the CTRE Pigeon2.
import com.ctre.phoenix6.hardware.Pigeon2;
import com.ctre.phoenix6.signals.StatusSignal;
Pigeon2 pigeon = new Pigeon2(0); // Device has CAN ID 0
// Get the yaw (heading) signal
StatusSignal<Double> angleSignal = pigeon.getYaw();
// Refresh the signal (important for getting the latest value) and get the value
angleSignal.refresh();
double angle = angleSignal.getValue();
// Or, in one line:
double angleOneLiner = pigeon.getYaw().getValue(); // This is less performant if you need multiple signals
Motors
We primarily use REV NEO brushless motors, controlled by a CANSparkMax controller.
CANSparkMax neoMotor = new CANSparkMax(0, MotorType.kBrushless);
// Set speed as a percentage (-1.0 to 1.0)
neoMotor.set(0.5);
// Set voltage directly (more repeatable)
neoMotor.setVoltage(6.0);
Solenoids / Pistons
Solenoids use pressurized air for linear motion.
Solenoid: Single-acting (air pushes, spring returns).
DoubleSolenoid: Double-acting (air pushes and returns).
import edu.wpi.first.wpilibj.PneumaticsModuleType;
import edu.wpi.first.wpilibj.Solenoid;
import edu.wpi.first.wpilibj.DoubleSolenoid;
// Single-acting
Solenoid singleSolenoid = new Solenoid(PneumaticsModuleType.REVPH, 0);
singleSolenoid.set(true); // Extend
// Double-acting
DoubleSolenoid doubleSolenoid = new DoubleSolenoid(PneumaticsModuleType.REVPH, 0, 1);
doubleSolenoid.set(DoubleSolenoid.Value.kForward); // Extend
doubleSolenoid.set(DoubleSolenoid.Value.kReverse); // Retract
doubleSolenoid.toggle(); // Flip state
DoubleSolenoid.Value currentState = doubleSolenoid.get();
When creating a device object, it's clean to configure it immediately. Java doesn't have Kotlin's apply block, but you can still group the configuration calls.
CANSparkMax neoMotor = new CANSparkMax(0, MotorType.kBrushless);
neoMotor.setIdleMode(CANSparkMax.IdleMode.kBrake);
neoMotor.setSmartCurrentLimit(40);
neoMotor.setInverted(false);
Joysticks and gamepads are connected to the Driver Station PC.
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.XboxController;
// Joystick
Joystick joystick = new Joystick(0);
double xAxis = joystick.getX();
boolean button1 = joystick.getRawButton(1);
// Xbox Controller
XboxController controller = new XboxController(0);
double leftX = controller.getLeftX();
boolean aButton = controller.getAButton();
AdvantageKit is a library for creating abstract interfaces for hardware, which makes logging and simulation much easier. The core concept is the IO Layer.
An IO Layer is a class that exposes a set of methods for interacting with a specific piece or group of hardware (e.g., a gripper, a drivetrain). It abstracts away the hardware details, making it easy to swap implementations (e.g., from real hardware to a simulation version) without changing the robot's main logic.
This involves two parts:
The Interface: A Java interface that defines the methods for controlling the hardware and includes a nested Inputs class for reading sensor data.
Implementations: Concrete classes that implement the interface for real hardware, simulated hardware, or even for log replay.
The IO Interface
The interface contains control methods (like openGripper()) and a nested Inputs class that implements LoggableInputs.
// In GripperIO.java
import org.littletonrobotics.junction.LoggableInputs;
import org.littletonrobotics.junction.LogTable;
import org.littletonrobotics.junction.AutoLog;
public interface GripperIO {
@AutoLog
class GripperIOInputs {
public boolean isOpen = false;
public boolean holdingCube = false;
public double cubeDistanceInches = 0.0;
}
default void updateInputs(GripperIOInputs inputs) {}
default void openGripper() {}
default void closeGripper() {}
}
Note: AdvantageKit's @AutoLog annotation on the inputs class automatically generates the toLog and fromLog methods at compile time, simplifying the code.
The Inputs Class
The Inputs class is a container for all data read from the hardware (e.g., sensor values, motor positions). In each robot loop, the IO implementation updates an instance of this Inputs object. Your robot's logic then reads from this object. This separates "reading" from "writing" and allows AdvantageKit to log all inputs to your system.
Rule of Thumb:
Input: Anything read from a sensor or device (motor voltage, encoder position, limit switch state).
Output: Anything calculated by your logic and sent to the hardware (desired motor speed, target position). Outputs are logged separately.
The IO Implementation
This is a concrete class that implements the interface and interacts with actual hardware.
// In GripperIOSolenoids.java
import edu.wpi.first.wpilibj.DoubleSolenoid;
import edu.wpi.first.wpilibj.Ultrasonic;
import edu.wpi.first.wpilibj.PneumaticsModuleType;
public class GripperIOSolenoids implements GripperIO {
private final DoubleSolenoid solenoid;
private final Ultrasonic sensor;
public GripperIOSolenoids() {
solenoid = new DoubleSolenoid(PneumaticsModuleType.REVPH, 0, 1);
sensor = new Ultrasonic(0, 1);
}
@Override
public void updateInputs(GripperIOInputs inputs) {
inputs.isOpen = solenoid.get() == DoubleSolenoid.Value.kForward;
inputs.cubeDistanceInches = sensor.getRangeInches();
inputs.holdingCube = inputs.cubeDistanceInches < 4.0; // e.g., < 4 inches
}
@Override
public void openGripper() {
solenoid.set(DoubleSolenoid.Value.kForward);
}
@Override
public void closeGripper() {
solenoid.set(DoubleSolenoid.Value.kReverse);
}
}
Now we can build a subsystem that uses our IO layer. The subsystem's job is to manage the IO layer, process the inputs, and provide command factories for robot logic.
// In Gripper.java
import org.littletonrobotics.junction.Logger;
import edu.wpi.first.wpilibj.RobotBase;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
public class Gripper extends SubsystemBase {
private final GripperIO io;
private final GripperIOInputsAutoLogged inputs = new GripperIOInputsAutoLogged();
public Gripper() {
if (RobotBase.isReal()) {
io = new GripperIOSolenoids();
} else {
// In a real project, this would be a simulation-specific class
io = new GripperIO() {};
}
}
@Override
public void periodic() {
io.updateInputs(inputs);
Logger.processInputs("Gripper", inputs);
}
public Command openGripper() {
return run(io::openGripper).until(() -> inputs.isOpen);
}
public Command closeGripper() {
return run(io::closeGripper).until(() -> !inputs.isOpen);
}
public Command grabCube() {
return Commands.sequence(
openGripper(),
Commands.waitUntil(() -> inputs.cubeDistanceInches < 4.0),
closeGripper()
);
}
}
Key points:
The subsystem constructor checks if the robot is real or simulated and instantiates the correct IO implementation.
periodic() is called every loop. It calls io.updateInputs() to get fresh sensor data and then Logger.processInputs() to log it.
Command factories (openGripper, closeGripper) use the io object to actuate hardware and the inputs object to check for conditions.
Besides logging inputs, you should also log the outputs of your control logic for debugging. This includes things like the robot's estimated pose, the trajectory it's following, or target setpoints.
Use Logger.recordOutput() in the subsystem's periodic() method.
// In a Drivetrain subsystem's periodic() method
import org.littletonrobotics.junction.Logger;
import edu.wpi.first.math.geometry.Pose2d;
// ... inside periodic() ...
// Assume 'odometry' is an Odometry object that provides the current pose
Logger.recordOutput("Drivetrain/EstimatedPose", odometry.getPoseMeters());
// Logging an array of poses (e.g. from vision)
// Assume 'visionPoses' is a Pose2d[]
Logger.recordOutput("Drivetrain/VisionPoses", visionPoses);
AdvantageKit can automatically serialize many WPILib objects, including Pose2d and arrays.
Follow the AdvantageKit installation guide through adding @AutoLog. Instead of the suggested robotInit() block, use:
Logger.getInstance().recordMetadata("ProjectName", "KitbotExample");
if (isReal()) {
Logger.getInstance().addDataReceiver(new WPILOGWriter("/media/sda1/"));
Logger.getInstance().addDataReceiver(new NT4Publisher());
new PowerDistribution(1, ModuleType.kRev);
} else {
Logger.getInstance().addDataReceiver(new NT4Publisher());
}
Logger.getInstance().start();
Define inputs you’ll log and the methods the subsystem will use.
package frc.robot.subsystems.drivetrain;
import org.littletonrobotics.junction.AutoLog;
public interface DrivetrainIO {
@AutoLog
public static class DrivetrainIOInputs {
public double leftOutputVolts = 0.0;
public double rightOutputVolts = 0.0;
public double leftVelocityMetersPerSecond = 0.0;
public double rightVelocityMetersPerSecond = 0.0;
public double leftPositionMeters = 0.0;
public double rightPositionMeters = 0.0;
public double[] leftCurrentAmps = new double[0];
public double[] leftTempCelsius = new double[0];
public double[] rightCurrentAmps = new double[0];
public double[] rightTempCelsius = new double[0];
}
public abstract void updateInputs(DrivetrainIOInputs inputs);
public abstract void setVolts(double left, double right);
}
Naming with units is critical to avoid confusion.
public class DrivetrainIOSim implements DrivetrainIO {
TalonFX leftFalcon = new TalonFX(Constants.drivetrainLeftFalconID);
TalonFX rightFalcon = new TalonFX(Constants.drivetrainRightFalconID);
VoltageOut leftVoltage = new VoltageOut(0);
VoltageOut rightVoltage = new VoltageOut(0);
DifferentialDrivetrainSim physicsSim = DifferentialDrivetrainSim.createKitbotSim(
KitbotMotor.kDoubleFalcon500PerSide,
KitbotGearing.k8p45,
KitbotWheelSize.kSixInch,
null);
@Override
public void setVolts(double left, double right) {
leftFalcon.setControl(leftVoltage.withOutput(left));
rightFalcon.setControl(rightVoltage.withOutput(right));
}
@Override
public void updateInputs(DrivetrainIOInputs inputs) {
physicsSim.update(0.020);
var leftSim = leftFalcon.getSimState();
var rightSim = rightFalcon.getSimState();
// Battery sag realism
leftSim.setSupplyVoltage(RoboRioSim.getVInVoltage());
rightSim.setSupplyVoltage(RoboRioSim.getVInVoltage());
physicsSim.setInputs(leftSim.getMotorVoltage(), rightSim.getMotorVoltage());
inputs.leftOutputVolts = leftSim.getMotorVoltage();
inputs.rightOutputVolts = rightSim.getMotorVoltage();
inputs.leftCurrentAmps = new double[] { leftSim.getTorqueCurrent() };
inputs.rightCurrentAmps = new double[] { rightSim.getTorqueCurrent() };
inputs.leftTempCelsius = new double[0];
inputs.rightTempCelsius = new double[0];
inputs.leftVelocityMetersPerSecond = physicsSim.getLeftVelocityMetersPerSecond();
inputs.rightVelocityMetersPerSecond = physicsSim.getRightVelocityMetersPerSecond();
inputs.leftPositionMeters = physicsSim.getLeftPositionMeters();
inputs.rightPositionMeters = physicsSim.getRightPositionMeters();
}
}
Replace direct motor usage with the IO layer and log inputs each loop.
public class DrivetrainSubsystem extends SubsystemBase {
DrivetrainIO io = new DrivetrainIOSim();
DrivetrainIOInputsAutoLogged inputs = new DrivetrainIOInputsAutoLogged();
DifferentialDriveOdometry odometry = new DifferentialDriveOdometry(new Rotation2d(), 0, 0);
@Override
public void periodic() {
io.updateInputs(inputs);
Logger.processInputs("Drivetrain", inputs);
// Fudged heading from wheel speeds (sim-only approximation)
odometry.update(
odometry.getPoseMeters().getRotation().plus(
Rotation2d.fromRadians(
(inputs.leftVelocityMetersPerSecond - inputs.rightVelocityMetersPerSecond)
* 0.020 / Units.inchesToMeters(26))),
inputs.leftPositionMeters,
inputs.rightPositionMeters);
Logger.recordOutput("Drivebase Pose", odometry.getPoseMeters());
}
private void setVoltages(double left, double right) {
io.setVolts(left, right);
}
}
You now have a fully simulated drivetrain with logged IO and field pose.
AdvantageKit's IO architecture is a powerful pattern for building testable and maintainable robot code. By decoupling your subsystems from direct hardware calls, you can easily switch between real and simulated environments, and the comprehensive logging provides incredible insight for debugging and analysis.