From ffc1c0cd8b83e5344b64436311f4bed0c47b60cc Mon Sep 17 00:00:00 2001 From: Bradley Bickford Date: Tue, 3 Feb 2026 18:32:32 -0500 Subject: [PATCH] Adding module zeroing constants and a few other minor changes from 2/3 build session --- .../robot/constants/DrivetrainConstants.java | 8 +++---- .../java/frc/robot/subsystems/Drivetrain.java | 16 ++++++------- .../frc/robot/utilities/SparkMAXTester.java | 23 +++++++++++++++++++ .../frc/robot/utilities/SwerveModule.java | 1 + 4 files changed, 36 insertions(+), 12 deletions(-) create mode 100644 src/main/java/frc/robot/utilities/SparkMAXTester.java diff --git a/src/main/java/frc/robot/constants/DrivetrainConstants.java b/src/main/java/frc/robot/constants/DrivetrainConstants.java index f4d8d61..e8b35fd 100644 --- a/src/main/java/frc/robot/constants/DrivetrainConstants.java +++ b/src/main/java/frc/robot/constants/DrivetrainConstants.java @@ -12,10 +12,10 @@ public class DrivetrainConstants { public static final double kTrackWidth = Units.inchesToMeters(23.75); public static final double kWheelBase = Units.inchesToMeters(18.75); - public static final double kFrontLeftMagEncoderOffset = 2.98; - public static final double kFrontRightMagEncoderOffset = 1.18; - public static final double kRearLeftMagEncoderOffset = 3.69; - public static final double kRearRightMagEncoderOffset = 2.54; + public static final double kFrontLeftMagEncoderOffset = 2.965; + public static final double kFrontRightMagEncoderOffset = 1.120; + public static final double kRearLeftMagEncoderOffset = 3.761; + public static final double kRearRightMagEncoderOffset = 2.573; public static final int kFrontLeftDrivingCANID = 0; public static final int kFrontRightDrivingCANID = 3; diff --git a/src/main/java/frc/robot/subsystems/Drivetrain.java b/src/main/java/frc/robot/subsystems/Drivetrain.java index 3281da4..b0eefd0 100644 --- a/src/main/java/frc/robot/subsystems/Drivetrain.java +++ b/src/main/java/frc/robot/subsystems/Drivetrain.java @@ -48,34 +48,34 @@ public class Drivetrain extends SubsystemBase { frontLeft = new SwerveModule( "FrontLeft", DrivetrainConstants.kFrontLeftDrivingCANID, - DrivetrainConstants.kFrontLeftTurningCANID);/*, + DrivetrainConstants.kFrontLeftTurningCANID, DrivetrainConstants.kFrontLeftAnalogInPort, DrivetrainConstants.kFrontLeftMagEncoderOffset - ); */ + ); frontRight = new SwerveModule( "FrontRight", DrivetrainConstants.kFrontRightDrivingCANID, - DrivetrainConstants.kFrontRightTurningCANID);/*, + DrivetrainConstants.kFrontRightTurningCANID, DrivetrainConstants.kFrontRightAnalogInPort, DrivetrainConstants.kFrontRightMagEncoderOffset - );*/ + ); rearLeft = new SwerveModule( "RearLeft", DrivetrainConstants.kRearLeftDrivingCANID, - DrivetrainConstants.kRearLeftTurningCANID);/*, + DrivetrainConstants.kRearLeftTurningCANID, DrivetrainConstants.kRearLeftAnalogInPort, DrivetrainConstants.kRearLeftMagEncoderOffset - ); */ + ); rearRight = new SwerveModule( "RearRight", DrivetrainConstants.kRearRightDrivingCANID, - DrivetrainConstants.kRearRightTurningCANID);/*, + DrivetrainConstants.kRearRightTurningCANID, DrivetrainConstants.kRearRightAnalogInPort, DrivetrainConstants.kRearRightMagEncoderOffset - ); */ + ); gyro = new AHRS(NavXComType.kMXP_SPI); diff --git a/src/main/java/frc/robot/utilities/SparkMAXTester.java b/src/main/java/frc/robot/utilities/SparkMAXTester.java new file mode 100644 index 0000000..2967757 --- /dev/null +++ b/src/main/java/frc/robot/utilities/SparkMAXTester.java @@ -0,0 +1,23 @@ +package frc.robot.utilities; + +import java.util.function.DoubleSupplier; + +import com.revrobotics.spark.SparkMax; +import com.revrobotics.spark.SparkLowLevel.MotorType; + +import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.SubsystemBase; + +public class SparkMAXTester extends SubsystemBase { + private SparkMax spark; + + public SparkMAXTester(int deviceID) { + spark = new SparkMax(deviceID, MotorType.kBrushless); + } + + public Command setSpeed(DoubleSupplier speed) { + return run(() -> { + spark.set(speed.getAsDouble()); + }); + } +} diff --git a/src/main/java/frc/robot/utilities/SwerveModule.java b/src/main/java/frc/robot/utilities/SwerveModule.java index ccc0169..9aaa1ba 100644 --- a/src/main/java/frc/robot/utilities/SwerveModule.java +++ b/src/main/java/frc/robot/utilities/SwerveModule.java @@ -134,6 +134,7 @@ public class SwerveModule { } public void periodic() { + if(!isAbsoluteEncoderDisabled) { Logger.recordOutput(moduleName + "/AbsoluteEncoder/Position", turningAbsoluteEncoder.get()); }