@@ -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