From 29a8090e6ba71dbadcb5553000b2ccf07a610f36 Mon Sep 17 00:00:00 2001 From: Rango813 Date: Sat, 27 Jan 2024 14:22:52 -0600 Subject: [PATCH] linting --- src/main/java/frc/lib/math/Conversions.java | 4 ++-- src/main/java/frc/lib/util/swerve/SwerveModule.java | 10 ++++++---- .../java/frc/lib/util/swerve/SwerveModuleReal.java | 4 ++++ src/main/java/frc/robot/Constants.java | 3 ++- .../java/frc/robot/subsystems/swerve/SwerveIO.java | 1 + 5 files changed, 15 insertions(+), 7 deletions(-) diff --git a/src/main/java/frc/lib/math/Conversions.java b/src/main/java/frc/lib/math/Conversions.java index 0e976e99..9a702763 100644 --- a/src/main/java/frc/lib/math/Conversions.java +++ b/src/main/java/frc/lib/math/Conversions.java @@ -10,7 +10,7 @@ public class Conversions { * @param circumference Wheel Circumference: (in Meters) * @return Wheel Velocity: (in Meters per Second) */ - public static double RPSToMPS(double wheelRPS, double circumference) { + public static double rotationPerSecondToMetersPerSecond(double wheelRPS, double circumference) { double wheelMPS = wheelRPS * circumference; return wheelMPS; } @@ -20,7 +20,7 @@ public static double RPSToMPS(double wheelRPS, double circumference) { * @param circumference Wheel Circumference: (in Meters) * @return Wheel Velocity: (in Rotations per Second) */ - public static double MPSToRPS(double wheelMPS, double circumference) { + public static double metersPerSecondToRotationPerSecond(double wheelMPS, double circumference) { double wheelRPS = wheelMPS / circumference; return wheelRPS; } diff --git a/src/main/java/frc/lib/util/swerve/SwerveModule.java b/src/main/java/frc/lib/util/swerve/SwerveModule.java index 5b0c5a3f..ea695154 100644 --- a/src/main/java/frc/lib/util/swerve/SwerveModule.java +++ b/src/main/java/frc/lib/util/swerve/SwerveModule.java @@ -11,7 +11,9 @@ import frc.lib.math.Conversions; import frc.robot.Constants; - +/** + * Swerve Module Subsystem + */ public class SwerveModule { public int moduleNumber; private Rotation2d angleOffset; @@ -82,8 +84,8 @@ private void setSpeed(SwerveModuleState desiredState, boolean isOpenLoop) { io.setDriveMotor(driveDutyCycle); inputs.driveMotorSelectedSensorVelocity = driveDutyCycle.Output; } else { - driveVelocity.Velocity = Conversions.MPSToRPS(desiredState.speedMetersPerSecond, - Constants.Swerve.wheelCircumference); + driveVelocity.Velocity = Conversions.metersPerSecondToRotationPerSecond( + desiredState.speedMetersPerSecond, Constants.Swerve.wheelCircumference); driveVelocity.FeedForward = driveFeedForward.calculate(desiredState.speedMetersPerSecond); io.setDriveMotor(driveVelocity); @@ -116,7 +118,7 @@ public void resetToAbsolute() { */ public SwerveModuleState getState() { return new SwerveModuleState( - Conversions.RPSToMPS(inputs.driveMotorSelectedSensorVelocity, + Conversions.rotationPerSecondToMetersPerSecond(inputs.driveMotorSelectedSensorVelocity, Constants.Swerve.wheelCircumference), Rotation2d.fromRotations(inputs.angleMotorSelectedPosition)); } diff --git a/src/main/java/frc/lib/util/swerve/SwerveModuleReal.java b/src/main/java/frc/lib/util/swerve/SwerveModuleReal.java index 325c72c1..d8317e0c 100644 --- a/src/main/java/frc/lib/util/swerve/SwerveModuleReal.java +++ b/src/main/java/frc/lib/util/swerve/SwerveModuleReal.java @@ -8,6 +8,9 @@ import edu.wpi.first.math.geometry.Rotation2d; import frc.robot.Constants; +/** + * Swerve Module IO + */ public class SwerveModuleReal implements SwerveModuleIO { private TalonFX mAngleMotor; @@ -17,6 +20,7 @@ public class SwerveModuleReal implements SwerveModuleIO { private TalonFXConfiguration swerveDriveFXConfig = new TalonFXConfiguration(); private CANcoderConfiguration swerveCANcoderConfig = new CANcoderConfiguration(); + /** Instantiating motors and Encoders */ public SwerveModuleReal(int moduleNumber, int driveMotorID, int angleMotorID, int cancoderID, Rotation2d angleOffset) { diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 982fce7c..a6c19ad5 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -175,7 +175,7 @@ public static final class Mod3 { // Drive base radius (distance from center to furthest module) maxSpeed, MOD0_MODOFFSET.getNorm(), new ReplanningConfig()); } - + /** Auto constants */ public static final class AutoConstants { public static final double kMaxSpeedMetersPerSecond = 3; public static final double kMaxAccelerationMetersPerSecondSquared = 3; @@ -223,6 +223,7 @@ public static final class ElevatorWristConstants { /** * Pneumatics CAN id constants. */ + public static final class Pneumatics { } diff --git a/src/main/java/frc/robot/subsystems/swerve/SwerveIO.java b/src/main/java/frc/robot/subsystems/swerve/SwerveIO.java index 8edf500f..442a1e3d 100644 --- a/src/main/java/frc/robot/subsystems/swerve/SwerveIO.java +++ b/src/main/java/frc/robot/subsystems/swerve/SwerveIO.java @@ -17,6 +17,7 @@ public static class SwerveInputs { public default void updateInputs(SwerveInputs inputs) {} + /** Instantiating SwerveModules */ public default SwerveModule createSwerveModule(int moduleNumber, int driveMotorID, int angleMotorID, int cancoderID, Rotation2d angleOffset) { return new SwerveModule(moduleNumber, driveMotorID, angleMotorID, cancoderID, angleOffset,