diff --git a/src/main/java/frc/robot/subsystems/drive/MAXSwerveIO.java b/src/main/java/frc/robot/subsystems/drive/MAXSwerveIO.java index 538de0e..49f2589 100644 --- a/src/main/java/frc/robot/subsystems/drive/MAXSwerveIO.java +++ b/src/main/java/frc/robot/subsystems/drive/MAXSwerveIO.java @@ -15,6 +15,7 @@ import com.revrobotics.spark.SparkLowLevel.MotorType; import com.revrobotics.spark.SparkMax; +import edu.wpi.first.epilogue.Logged; import edu.wpi.first.math.geometry.Rotation2d; import frc.robot.subsystems.drive.swerve.MAXSwerveModuleIO; import frc.robot.subsystems.drive.swerve.SwerveModule; @@ -23,6 +24,7 @@ * IO for a swerve drive using REV MAXSwerve modules driven by a NEO motor and turned by a NEO 550 * motor. */ +@Logged public class MAXSwerveIO implements SwerveIO { private final SwerveModule frontLeft = new SwerveModule( diff --git a/src/main/java/frc/robot/subsystems/drive/SimSwerveIO.java b/src/main/java/frc/robot/subsystems/drive/SimSwerveIO.java index e434d83..a9c3a99 100644 --- a/src/main/java/frc/robot/subsystems/drive/SimSwerveIO.java +++ b/src/main/java/frc/robot/subsystems/drive/SimSwerveIO.java @@ -6,12 +6,14 @@ import static frc.robot.Constants.DriveConstants.rearLeftChassisAngularOffset; import static frc.robot.Constants.DriveConstants.rearRightChassisAngularOffset; +import edu.wpi.first.epilogue.Logged; import edu.wpi.first.math.geometry.Rotation2d; import frc.robot.sim.Simulation; import frc.robot.sim.SimulationContext; import frc.robot.subsystems.drive.swerve.SimModuleIO; import frc.robot.subsystems.drive.swerve.SwerveModule; +@Logged public class SimSwerveIO implements SwerveIO { private final SwerveModule frontLeft; private final SwerveModule frontRight;