From 88e568bff3d402f862d801142f78714ca2892b12 Mon Sep 17 00:00:00 2001 From: ACat701 <90939494+alicekuznetsov@users.noreply.github.com> Date: Fri, 30 May 2025 18:03:58 -0700 Subject: [PATCH 1/2] Require CANBus name as parameter to SN_SwerveModule --- .../com/frcteam3255/components/swerve/SN_SwerveModule.java | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/src/main/java/com/frcteam3255/components/swerve/SN_SwerveModule.java b/src/main/java/com/frcteam3255/components/swerve/SN_SwerveModule.java index 5b1e77c..730e358 100644 --- a/src/main/java/com/frcteam3255/components/swerve/SN_SwerveModule.java +++ b/src/main/java/com/frcteam3255/components/swerve/SN_SwerveModule.java @@ -50,7 +50,6 @@ public class SN_SwerveModule extends SubsystemBase { public static InvertedValue driveInversion = InvertedValue.CounterClockwise_Positive; public static InvertedValue steerInversion = InvertedValue.Clockwise_Positive; public static SensorDirectionValue cancoderInversion = SensorDirectionValue.CounterClockwise_Positive; - public static String CANBusName = "Swerve"; public static double minimumSteerSpeedPercent = 0.01; // -*- Static Physical Constants -*- @@ -85,9 +84,11 @@ public class SN_SwerveModule extends SubsystemBase { * The offset of the CANcoder in rotations. This is typically * obtained by aligning all of the wheels in the appropriate * direction and then copying the Raw Absolute encoder value. + * @param CANBusName + * The name of the CANBus that the module is connected to. */ public SN_SwerveModule(int moduleNumber, int driveMotorID, int steerMotorID, int absoluteEncoderID, - double absoluteEncoderOffset) { + double absoluteEncoderOffset, String CANBusName) { simTimer.start(); From 573f3f0ad0e0ee55a32a6a05dfd87fa1a2289a42 Mon Sep 17 00:00:00 2001 From: ACat701 <90939494+alicekuznetsov@users.noreply.github.com> Date: Fri, 30 May 2025 18:09:31 -0700 Subject: [PATCH 2/2] whoops --- .../frcteam3255/components/swerve/SN_SuperSwerve.java | 1 - .../frcteam3255/components/swerve/SN_SwerveModule.java | 10 ++++++---- 2 files changed, 6 insertions(+), 5 deletions(-) diff --git a/src/main/java/com/frcteam3255/components/swerve/SN_SuperSwerve.java b/src/main/java/com/frcteam3255/components/swerve/SN_SuperSwerve.java index 64f8267..0603707 100644 --- a/src/main/java/com/frcteam3255/components/swerve/SN_SuperSwerve.java +++ b/src/main/java/com/frcteam3255/components/swerve/SN_SuperSwerve.java @@ -155,7 +155,6 @@ public SN_SuperSwerve(SN_SwerveConstants swerveConstants, SN_SwerveModule[] modu SN_SwerveModule.driveGearRatio = swerveConstants.driveGearRatio; SN_SwerveModule.steerGearRatio = swerveConstants.steerGearRatio; - SN_SwerveModule.CANBusName = CANBusName; SN_SwerveModule.minimumSteerSpeedPercent = minimumSteerPercent; SN_SwerveModule.driveInversion = driveInversion; diff --git a/src/main/java/com/frcteam3255/components/swerve/SN_SwerveModule.java b/src/main/java/com/frcteam3255/components/swerve/SN_SwerveModule.java index 730e358..d1ecca7 100644 --- a/src/main/java/com/frcteam3255/components/swerve/SN_SwerveModule.java +++ b/src/main/java/com/frcteam3255/components/swerve/SN_SwerveModule.java @@ -137,7 +137,7 @@ public void configure() { */ public double getRawAbsoluteEncoder() { // TODO: change to units using .getValue - return absoluteEncoder.getAbsolutePosition().getValueAsDouble(); + return absoluteEncoder.getAbsolutePosition().getValueAsDouble(); } /** @@ -180,9 +180,10 @@ public void resetDriveMotorEncoder() { public SwerveModuleState getActualModuleState() { // TODO: change to units using .getValue double velocity = SN_Math.rotationsToMeters(driveMotor.getVelocity().getValueAsDouble(), wheelCircumference, 1); - + // TODO: change to units using .getValue - Rotation2d angle = Rotation2d.fromDegrees(Units.rotationsToDegrees(steerMotor.getPosition().getValueAsDouble())); + Rotation2d angle = Rotation2d + .fromDegrees(Units.rotationsToDegrees(steerMotor.getPosition().getValueAsDouble())); return new SwerveModuleState(velocity, angle); } @@ -213,7 +214,8 @@ public SwerveModulePosition getModulePosition() { // TODO: change to units using .getValue double distance = SN_Math.rotationsToMeters(driveMotor.getPosition().getValueAsDouble(), wheelCircumference, 1); // TODO: change to units using .getValue - Rotation2d angle = Rotation2d.fromDegrees(Units.rotationsToDegrees(steerMotor.getPosition().getValueAsDouble())); + Rotation2d angle = Rotation2d + .fromDegrees(Units.rotationsToDegrees(steerMotor.getPosition().getValueAsDouble())); return new SwerveModulePosition(distance, angle); }