|
| 1 | +--- |
| 2 | +title: AdvantageKit Reference |
| 3 | +layout: default |
| 4 | +nav_order: 11 |
| 5 | +parent: architecture |
| 6 | +--- |
| 7 | +# AdvantageKit Code Structure Reference |
| 8 | + |
| 9 | +This document contains a quick reference for how we structure our code. |
| 10 | +It should be used when planning out the structure of a subsystem. |
| 11 | + |
| 12 | +## Basic Layout |
| 13 | + |
| 14 | +```mermaid |
| 15 | +flowchart TD |
| 16 | + subgraph Subsystem |
| 17 | + A[Subsystem] |
| 18 | + end |
| 19 | + Subsystem-->IO |
| 20 | + subgraph IO |
| 21 | + direction LR |
| 22 | + B[IO]-->E[IOInputs] |
| 23 | + end |
| 24 | + IO-->IOImpl |
| 25 | + subgraph IOImpl |
| 26 | + C[IO Implementation Real] |
| 27 | + D[IO Implementation Sim] |
| 28 | + end |
| 29 | +``` |
| 30 | + |
| 31 | +This diagram shows the basic structure of an AKit Subsystem. |
| 32 | +It includes 3 layers: |
| 33 | + |
| 34 | +### Subsystem |
| 35 | + |
| 36 | +- The "subsystem" layer is a class which `extends SubsystemBase`. |
| 37 | +- This class should contain methods that return Commands for this subsystem. |
| 38 | +- This class should contain all higher-level control flow within this mechanism. |
| 39 | + - For instance, it could contain a `SwerveDriveOdometry` object to track a drivetrain's position. |
| 40 | + - It might contain information about the current target of a mechanism, or whether or not the mechanism has homed its position yet. |
| 41 | + - *Generally, this information should all be **"processed" information** that we derive from our IOInputs. |
| 42 | +- The `Subsystem` file will contain one `IO` instance and one `IOInputs` instance, conventionally called `io` and `inputs` respectively. |
| 43 | + |
| 44 | +### IO |
| 45 | + |
| 46 | +- The "IO" layer defines the interface with our hardware, as well as all the values we will log. |
| 47 | +- This includes an `interface` called `SubsystemIO` which defines a set of methods to interact with the hardware, such as `setVoltage` or `getPosition`. |
| 48 | +However, it doesn't define *how* to do them, because that's specific to each implementation. |
| 49 | +The interface just provides a template. |
| 50 | +- This class will also include an `updateInputs` method, which takes in an `IOInputs` object and updates it with the latest sensor data from the mechanism. |
| 51 | +- The `IOInputs` object is a class that contains various measurements and sensor data about the mechanism, like current draw, encoder position, and voltage output. |
| 52 | +- It is marked with `@AutoLog` which means all the inputs and outputs for the subsystem will be automatically recorded in the log, so we can play it back later. |
| 53 | + |
| 54 | +### IO Implementations |
| 55 | + |
| 56 | +- These are classes which `implement` the aforementioned `IO` class. |
| 57 | +- This means they will specify how to do all of the methods defined in the `IO` class. |
| 58 | +- Generally we will have 2 types of `IOImplementation`, `IOSim` and `IOReal`. |
| 59 | + - `IOReal` defines its methods to command real hardware to have real outputs. |
| 60 | + - `IOSim` often looks similar to `IOReal`, but will have some behaviour added to fake the behaviour of real world physics. |
| 61 | + This can include a physics sim which approximates physical behaviour, setting outputs which we can't sim to a default value (like temperature), or other ways of "faking" real world behaviour. |
| 62 | +- `IOImplementation`s will contain the actual objects such as `TalonFX`s (for `IOReal`) or `DCMotorSim`s (for `IOSim`). |
| 63 | + |
| 64 | +## Intake Example |
| 65 | + |
| 66 | +<img src="../../assets/2025OffsznIntake.png" alt="A cad render of the intake from our 2025 offseason robot" width="600"/> |
| 67 | + |
| 68 | +This example will cover how the code for an intake such as the one above might be set up. |
| 69 | + |
| 70 | +```mermaid |
| 71 | +flowchart TD |
| 72 | + subgraph Subsystem |
| 73 | + A[IntakeSubsystem] |
| 74 | + end |
| 75 | + Subsystem-->IO |
| 76 | + subgraph IO |
| 77 | + direction LR |
| 78 | + B[IntakeIO]-->E[IntakeIOInputs] |
| 79 | + end |
| 80 | + IO-->IOImpl |
| 81 | + subgraph IOImpl |
| 82 | + C[IntakeIOReal] |
| 83 | + D[IntakeIOSim] |
| 84 | + end |
| 85 | +``` |
| 86 | + |
| 87 | +Let's start by defining the methods in the `IntakeIO` interface. |
| 88 | +There are two motors on this slapdown intake--one that controls the pivot, and one that controls the rollers. |
| 89 | +The intake needs to set its position (extended or retracted), so we will need a `setAngle(Rotation2d angle)` method. |
| 90 | +We will also need a way to set the rollers' output, so let's add a `setRollerVoltage(double volts)` method. |
| 91 | +For convenience, let's add a method `stop()` that calls `setRollerVoltage()` with a voltage of 0. |
| 92 | + |
| 93 | +We also need to add our `IntakeIOInputs` to the `IntakeIO` file. |
| 94 | +This should contain all of the sensor information we need to know about our intake so that we can debug its behaviour with logs. |
| 95 | +Then we can add our logged fields for the motor. |
| 96 | + |
| 97 | +Here is a list of common logged fields for motors: |
| 98 | + |
| 99 | +- Velocity (Often but not always in rotations per second) |
| 100 | + - This is the main field we care about to see if the motor is moving. |
| 101 | +- Current draw (Amps) |
| 102 | + - This lets us see if the motor is stalling (trying to move but stuck) as well as how much energy the motor is using. |
| 103 | +- Temperature (Celsius) |
| 104 | + - If a motor gets too hot it will turn itself off to protect its electronics. |
| 105 | + This lets us see if we are having issues related to that. |
| 106 | + In addition, motors are less efficient as they heat up. |
| 107 | +- Voltage (Voltage) |
| 108 | + - This lets us see how much we are commanding our motors to move. |
| 109 | +- Position (Rotations or inches, often after a gear reduction) |
| 110 | + - This lets us track the position of the motor and its corresponding mechanism. |
| 111 | + |
| 112 | +We can add all of these values into our `IntakeIOInputs` class. |
| 113 | + |
| 114 | +Finally, add a `updateInputs(IntakeIOInputs inputs)` method that our `IOImplementation`s can call to record these values. |
| 115 | +Our `IntakeIO` file should look something like this now: |
| 116 | + |
| 117 | +```Java |
| 118 | +// Imports go here |
| 119 | + |
| 120 | +public interface IntakeIO { |
| 121 | + @AutoLog |
| 122 | + public class IntakeIOInputs { |
| 123 | + |
| 124 | + // Pivot motor values |
| 125 | + public double pivotVelocityRotationsPerSec; |
| 126 | + public double pivotCurrentDrawAmps; |
| 127 | + public double pivotTemperatureCelsius; |
| 128 | + public double pivotVoltage; |
| 129 | + public Rotation2d pivotMotorPosition; |
| 130 | + |
| 131 | + // Roller motor values |
| 132 | + public double rollerVelocityRotationsPerSec; |
| 133 | + public double rollerCurrentDrawAmps; |
| 134 | + public double rollerTemperatureCelsius; |
| 135 | + public double rollerVoltage; |
| 136 | + } |
| 137 | + |
| 138 | + // Methods that IOImplementations will implement |
| 139 | + public void setAngle(Rotation2d angle); |
| 140 | + |
| 141 | + public void setRollerVoltage(double volts); |
| 142 | + |
| 143 | + // Note the use of "default" |
| 144 | + // This means that we don't have to re-implement this method in each IOImplementation, because it will default to |
| 145 | + // whatever the specific implementation of setVoltage() is |
| 146 | + public default void stop() { |
| 147 | + setRollerVoltage(0); |
| 148 | + } |
| 149 | + |
| 150 | + public void updateInputs(IntakeIOInputs inputs); |
| 151 | +} |
| 152 | +``` |
| 153 | + |
| 154 | +Next, let's write `IntakeIOReal`. |
| 155 | +This will contain all of the hardware we want to interact with on the real robot. |
| 156 | + |
| 157 | +First, we will need to define the hardware we want to use. |
| 158 | +In this case, they will be two `TalonFX`s. |
| 159 | + |
| 160 | +```Java |
| 161 | +private final TalonFX pivot = new TalonFX(IntakeSubsystem.PIVOT_MOTOR_ID); |
| 162 | +private final TalonFX roller = new TalonFX(IntakeSubsystem.ROLLER_MOTOR_ID); |
| 163 | +``` |
| 164 | + |
| 165 | +Next we will need to implement each of the methods from `IntakeIO`. |
| 166 | +Each should `@Override` the template method. |
| 167 | +For the sake of brevity, I won't cover that in detail here. *MAKE SUBSYSTEM WALKTHROUGH AND LINK HERE* |
| 168 | + |
| 169 | +In the end you should have something like: |
| 170 | + |
| 171 | +```Java |
| 172 | +public class IntakeIOReal implements IntakeIO { |
| 173 | + private final TalonFX pivot = new TalonFX(IntakeSubsystem.PIVOT_MOTOR_ID); |
| 174 | + private final TalonFX roller = new TalonFX(IntakeSubsystem.ROLLER_MOTOR_ID); |
| 175 | + |
| 176 | + @Override |
| 177 | + public void updateInputs(IntakeIOInputs inputs) { |
| 178 | + // Note that the exact calls here are just examples, and might not work if copy-pasted |
| 179 | + |
| 180 | + inputs.pivotVelocityRotationsPerSec = pivot.getVelocity(); |
| 181 | + inputs.pivotCurrentDrawAmps = pivot.getStatorCurrent(); |
| 182 | + inputs.pivotTemperatureCelsius = pivot.getDeviceTemp(); |
| 183 | + inputs.pivotVoltage = pivot.getMotorVoltage(); |
| 184 | + inputs.pivotMotorPosition = pivot.getMotorPosition(); |
| 185 | + |
| 186 | + // Roller motor values |
| 187 | + inputs.rollerVelocityRotationsPerSec = roller.getVelocity(); |
| 188 | + inputs.rollerCurrentDrawAmps = roller.getStatorCurrent(); |
| 189 | + inputs.rollerTemperatureCelsius = roller.getDeviceTemp(); |
| 190 | + inputs.rollerVoltage = roller.getMotorVoltage(); |
| 191 | + } |
| 192 | + |
| 193 | + @Override |
| 194 | + public void setRollerVoltage(double volts) { |
| 195 | + roller.setVoltage(volts); |
| 196 | + } |
| 197 | + |
| 198 | + // Note how we don't need to define stop() because it has a default implementation that does what we want |
| 199 | + |
| 200 | + @Override |
| 201 | + public void setAngle(Rotation2d angle) { |
| 202 | + pivot.setAngle(angle); |
| 203 | + } |
| 204 | +} |
| 205 | +``` |
| 206 | + |
| 207 | +We can make a similar class for `IntakeIOSim`, although instead of getting motor outputs directly we would have to use `motor.getSimState()`. |
| 208 | +For more information about that, check the [CTRE docs](https://pro.docs.ctr-electronics.com/en/stable/docs/api-reference/simulation/simulation-intro.html). |
| 209 | + |
| 210 | +Finally, let's write the `IntakeSubsystem` class. |
| 211 | +This class will include an instance of `IntakeIO` and an instance of `IntakeIOInputs`. |
| 212 | +It will also contain Command factories to allow the rest of our code to interface with it. |
| 213 | + |
| 214 | +Add the io and io inputs to the class: |
| 215 | + |
| 216 | +```Java |
| 217 | +// Snip imports |
| 218 | + |
| 219 | +public class IntakeSubsystem extends SubsystemBase { |
| 220 | + private final IntakeIO io; |
| 221 | + private final IntakeIOInputsAutoLogged inputs = new IntakeIOInputsAutoLogged(); |
| 222 | + |
| 223 | + public IntakeSubsystem(IntakeIO io) { |
| 224 | + // Pass in either the sim io or real io |
| 225 | + this.io = io; |
| 226 | + } |
| 227 | +} |
| 228 | +``` |
| 229 | + |
| 230 | +Then we can add a few Command factories to control the subsystem: |
| 231 | + |
| 232 | +```Java |
| 233 | +public Command intake(double volts) { |
| 234 | + return Commands.run(() -> { |
| 235 | + io.setAngle(INTAKE_ANGLE); |
| 236 | + io.setRollerVoltage(volts); |
| 237 | + }); |
| 238 | +} |
| 239 | + |
| 240 | +public Command stop() { |
| 241 | + return Commands.runOnce(() -> { |
| 242 | + io.setAngle(RETRACTED_ANGLE); |
| 243 | + io.stop(); |
| 244 | + }); |
| 245 | +} |
| 246 | +``` |
| 247 | + |
| 248 | +Finally, let's add our `periodic()` method to update and log our inputs. |
| 249 | + |
| 250 | +```Java |
| 251 | +@Override |
| 252 | +public void periodic() { |
| 253 | + io.updateInputs(); |
| 254 | + // Make sure to import the "littletonRobotics" Logger, not one of the other ones. |
| 255 | + Logger.processInputs("Intake", inputs); |
| 256 | +} |
| 257 | +``` |
| 258 | + |
| 259 | +Overall, `IntakeSubsystem` should roughly look like: |
| 260 | + |
| 261 | +```Java |
| 262 | +// Snip imports |
| 263 | + |
| 264 | +public class IntakeSubsystem extends SubsystemBase { |
| 265 | + IntakeIO io; |
| 266 | + IntakeIOInputsAutoLogged inputs; |
| 267 | + |
| 268 | + public IntakeSubsystem(IntakeIO io) { |
| 269 | + // Pass in either the sim io or real io |
| 270 | + this.io = io; |
| 271 | + inputs = new IntakeIOInputsAutoLogged(); |
| 272 | + } |
| 273 | + |
| 274 | + public Command intake(double volts) { |
| 275 | + return Commands.run(() -> { |
| 276 | + io.setAngle(INTAKE_ANGLE); |
| 277 | + io.setRollerVoltage(volts); |
| 278 | + }); |
| 279 | + } |
| 280 | + |
| 281 | + public Command stop() { |
| 282 | + return Commands.runOnce(() -> { |
| 283 | + io.setAngle(RETRACTED_ANGLE); |
| 284 | + io.stop(); |
| 285 | + }); |
| 286 | + } |
| 287 | + |
| 288 | + @Override |
| 289 | + public void periodic() { |
| 290 | + io.updateInputs(); |
| 291 | + // Make sure to import the "littletonRobotics" Logger, not one of the other ones. |
| 292 | + Logger.processInputs("Intake", inputs); |
| 293 | + } |
| 294 | +} |
| 295 | +``` |
| 296 | + |
| 297 | +### More complex subsystems |
| 298 | + |
| 299 | +The intake is a very simple to program subsystem, but more complex ones exist. |
| 300 | +A swerve drive might have the following set of classes: |
| 301 | + |
| 302 | +```mermaid |
| 303 | +flowchart TD |
| 304 | + subgraph Subsystem |
| 305 | + A[SwerveSubsystem] |
| 306 | + end |
| 307 | +
|
| 308 | + Subsystem--- 4x -->SwerveModuleIO |
| 309 | + subgraph SwerveModuleIO |
| 310 | + direction LR |
| 311 | + B[SwerveModuleIO]-->E[SwerveModuleIOInputs] |
| 312 | + end |
| 313 | + SwerveModuleIO-->SwerveModuleIOImpl |
| 314 | + subgraph SwerveModuleIOImpl |
| 315 | + C[SwerveModuleIOReal] |
| 316 | + D[SwerveModuleIOSim] |
| 317 | + end |
| 318 | +
|
| 319 | + Subsystem--->GyroIO |
| 320 | + subgraph GyroIO |
| 321 | + direction LR |
| 322 | + X[GyroIO]-->GyroIOInputs |
| 323 | + end |
| 324 | + GyroIO-->GyroIOImpl |
| 325 | + subgraph GyroIOImpl |
| 326 | + GyroIOReal |
| 327 | + GyroIOSim |
| 328 | + end |
| 329 | +``` |
| 330 | + |
| 331 | +This means that we will have one `SwerveSubsystem` class. |
| 332 | +Within that class, we will have 4 instances of `SwerveModuleIO` and its corresponding `SwerveModuleIOInputs`, one for each module. |
| 333 | +We will also have an instance of `GyroIO` and `GyroIOInputs`. |
| 334 | +The `SwerveSubsystem` file handles coordinating and combining data from these `IO`s, and each `IO` handles turning the control signals from the `Subsystem` into motion in the hardware (or sim!). |
0 commit comments