Skip to content

Commit 573f3f0

Browse files
whoops
1 parent 88e568b commit 573f3f0

File tree

2 files changed

+6
-5
lines changed

2 files changed

+6
-5
lines changed

src/main/java/com/frcteam3255/components/swerve/SN_SuperSwerve.java

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -155,7 +155,6 @@ public SN_SuperSwerve(SN_SwerveConstants swerveConstants, SN_SwerveModule[] modu
155155
SN_SwerveModule.driveGearRatio = swerveConstants.driveGearRatio;
156156
SN_SwerveModule.steerGearRatio = swerveConstants.steerGearRatio;
157157

158-
SN_SwerveModule.CANBusName = CANBusName;
159158
SN_SwerveModule.minimumSteerSpeedPercent = minimumSteerPercent;
160159

161160
SN_SwerveModule.driveInversion = driveInversion;

src/main/java/com/frcteam3255/components/swerve/SN_SwerveModule.java

Lines changed: 6 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -137,7 +137,7 @@ public void configure() {
137137
*/
138138
public double getRawAbsoluteEncoder() {
139139
// TODO: change to units using .getValue
140-
return absoluteEncoder.getAbsolutePosition().getValueAsDouble();
140+
return absoluteEncoder.getAbsolutePosition().getValueAsDouble();
141141
}
142142

143143
/**
@@ -180,9 +180,10 @@ public void resetDriveMotorEncoder() {
180180
public SwerveModuleState getActualModuleState() {
181181
// TODO: change to units using .getValue
182182
double velocity = SN_Math.rotationsToMeters(driveMotor.getVelocity().getValueAsDouble(), wheelCircumference, 1);
183-
183+
184184
// TODO: change to units using .getValue
185-
Rotation2d angle = Rotation2d.fromDegrees(Units.rotationsToDegrees(steerMotor.getPosition().getValueAsDouble()));
185+
Rotation2d angle = Rotation2d
186+
.fromDegrees(Units.rotationsToDegrees(steerMotor.getPosition().getValueAsDouble()));
186187

187188
return new SwerveModuleState(velocity, angle);
188189
}
@@ -213,7 +214,8 @@ public SwerveModulePosition getModulePosition() {
213214
// TODO: change to units using .getValue
214215
double distance = SN_Math.rotationsToMeters(driveMotor.getPosition().getValueAsDouble(), wheelCircumference, 1);
215216
// TODO: change to units using .getValue
216-
Rotation2d angle = Rotation2d.fromDegrees(Units.rotationsToDegrees(steerMotor.getPosition().getValueAsDouble()));
217+
Rotation2d angle = Rotation2d
218+
.fromDegrees(Units.rotationsToDegrees(steerMotor.getPosition().getValueAsDouble()));
217219

218220
return new SwerveModulePosition(distance, angle);
219221
}

0 commit comments

Comments
 (0)