Skip to content

Commit

Permalink
linting
Browse files Browse the repository at this point in the history
  • Loading branch information
Rango813 committed Jan 27, 2024
1 parent 4da8153 commit 29a8090
Show file tree
Hide file tree
Showing 5 changed files with 15 additions and 7 deletions.
4 changes: 2 additions & 2 deletions src/main/java/frc/lib/math/Conversions.java
Original file line number Diff line number Diff line change
Expand Up @@ -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;
}
Expand All @@ -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;
}
Expand Down
10 changes: 6 additions & 4 deletions src/main/java/frc/lib/util/swerve/SwerveModule.java
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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);
Expand Down Expand Up @@ -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));
}
Expand Down
4 changes: 4 additions & 0 deletions src/main/java/frc/lib/util/swerve/SwerveModuleReal.java
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand All @@ -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) {

Expand Down
3 changes: 2 additions & 1 deletion src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -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 {

Check warning on line 179 in src/main/java/frc/robot/Constants.java

View workflow job for this annotation

GitHub Actions / Linting

[testtool] reported by reviewdog 🐶 'CLASS_DEF' should be separated from previous line. Raw Output: /github/workspace/./src/main/java/frc/robot/Constants.java:179:5: warning: 'CLASS_DEF' should be separated from previous line. (com.puppycrawl.tools.checkstyle.checks.whitespace.EmptyLineSeparatorCheck)
public static final double kMaxSpeedMetersPerSecond = 3;
public static final double kMaxAccelerationMetersPerSecondSquared = 3;
Expand Down Expand Up @@ -223,6 +223,7 @@ public static final class ElevatorWristConstants {
/**
* Pneumatics CAN id constants.
*/

public static final class Pneumatics {
}

Expand Down
1 change: 1 addition & 0 deletions src/main/java/frc/robot/subsystems/swerve/SwerveIO.java
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand Down

0 comments on commit 29a8090

Please sign in to comment.