Skip to content
This repository has been archived by the owner on Nov 2, 2024. It is now read-only.

Commit

Permalink
fix linting
Browse files Browse the repository at this point in the history
  • Loading branch information
legoguy1000 committed Jan 27, 2024
1 parent f3d576f commit 4a482bc
Show file tree
Hide file tree
Showing 5 changed files with 20 additions and 4 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 @@ -12,7 +12,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 rpsToMPS(double wheelRPS, double circumference) {
double wheelMPS = wheelRPS * circumference;
return wheelMPS;
}
Expand All @@ -22,7 +22,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 mpsToRPS(double wheelMPS, double circumference) {
double wheelRPS = wheelMPS / circumference;
return wheelRPS;
}
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/lib/util/swerve/SwerveModule.java
Original file line number Diff line number Diff line change
Expand Up @@ -88,7 +88,7 @@ private void setSpeed(SwerveModuleState desiredState, boolean isOpenLoop) {
io.setDriveMotor(driveDutyCycle);
inputs.driveMotorSelectedSensorVelocity = driveDutyCycle.Output;
} else {
driveVelocity.Velocity = Conversions.MPSToRPS(desiredState.speedMetersPerSecond,
driveVelocity.Velocity = Conversions.mpsToRPS(desiredState.speedMetersPerSecond,
Constants.Swerve.WHEEL_CIRCUMFERENCE);
driveVelocity.FeedForward =
driveFeedForward.calculate(desiredState.speedMetersPerSecond);
Expand Down Expand Up @@ -122,7 +122,7 @@ public void resetToAbsolute() {
*/
public SwerveModuleState getState() {
return new SwerveModuleState(
Conversions.RPSToMPS(inputs.driveMotorSelectedSensorVelocity,
Conversions.rpsToMPS(inputs.driveMotorSelectedSensorVelocity,
Constants.Swerve.WHEEL_CIRCUMFERENCE),
Rotation2d.fromRotations(inputs.angleMotorSelectedPosition));
}
Expand Down
3 changes: 3 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 with real motors and sensors
*/
public class SwerveModuleReal implements SwerveModuleIO {
private TalonFX mAngleMotor;
private TalonFX mDriveMotor;
Expand Down
10 changes: 10 additions & 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,16 @@ public static class SwerveInputs {

public default void updateInputs(SwerveInputs inputs) {}

/**
* Create a Swerve Module for the repsective IO Layer

Check failure on line 21 in src/main/java/frc/robot/subsystems/swerve/SwerveIO.java

View workflow job for this annotation

GitHub Actions / Spell Check

repsective ==> respective
*
* @param moduleNumber The Module Number
* @param driveMotorID The Drive Motor CAN ID
* @param angleMotorID The Angle Motor CAN ID
* @param cancoderID The CANCode CAN ID
* @param angleOffset The Angle Offset in {@link Rotation2d}
* @return {@link SwerveModule}
*/
public default SwerveModule createSwerveModule(int moduleNumber, int driveMotorID,
int angleMotorID, int cancoderID, Rotation2d angleOffset) {
return new SwerveModule(moduleNumber, driveMotorID, angleMotorID, cancoderID, angleOffset,
Expand Down
3 changes: 3 additions & 0 deletions src/main/java/frc/robot/subsystems/swerve/SwerveReal.java
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,9 @@ public SwerveReal() {

}

/**
* Update Inputs
*/
@Override
public void updateInputs(SwerveInputs inputs) {
inputs.yaw = gyro.getYaw();
Expand Down

0 comments on commit 4a482bc

Please sign in to comment.