Skip to content

Commit 50740d8

Browse files
committed
try to fix ci / check
1 parent 180fa4c commit 50740d8

File tree

1 file changed

+21
-11
lines changed

1 file changed

+21
-11
lines changed

examples/maxswerve/subsystems/maxswervemodule.py

Lines changed: 21 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -24,12 +24,8 @@ def __init__(
2424
self.chassisAngularOffset = 0
2525
self.desiredState = SwerveModuleState(0.0, Rotation2d())
2626

27-
self.drivingSparkMax = SparkMax(
28-
drivingCANId, SparkMax.MotorType.kBrushless
29-
)
30-
self.turningSparkMax = SparkMax(
31-
turningCANId, SparkMax.MotorType.kBrushless
32-
)
27+
self.drivingSparkMax = SparkMax(drivingCANId, SparkMax.MotorType.kBrushless)
28+
self.turningSparkMax = SparkMax(turningCANId, SparkMax.MotorType.kBrushless)
3329

3430
self.drivingConfig = SparkMaxConfig()
3531
self.turningConfig = SparkMaxConfig()
@@ -39,8 +35,12 @@ def __init__(
3935
self.turningEncoder = self.turningSparkMax.getAbsoluteEncoder()
4036
self.drivingPidController = self.drivingSparkMax.getClosedLoopController()
4137
self.turningPidController = self.turningSparkMax.getClosedLoopController()
42-
self.drivingConfig.closedLoop.setFeedbackSensor(ClosedLoopConfig.FeedbackSensor.kPrimaryEncoder)
43-
self.turningConfig.closedLoop.setFeedbackSensor(ClosedLoopConfig.FeedbackSensor.kAbsoluteEncoder)
38+
self.drivingConfig.closedLoop.setFeedbackSensor(
39+
ClosedLoopConfig.FeedbackSensor.kPrimaryEncoder
40+
)
41+
self.turningConfig.closedLoop.setFeedbackSensor(
42+
ClosedLoopConfig.FeedbackSensor.kAbsoluteEncoder
43+
)
4444

4545
# Apply position and velocity conversion factors for the driving encoder. The
4646
# native units for position and velocity are rotations and RPM, respectively,
@@ -64,7 +64,9 @@ def __init__(
6464

6565
# Invert the turning encoder, since the output shaft rotates in the opposite direction of
6666
# the steering motor in the MAXSwerve Module.
67-
self.turningConfig.absoluteEncoder.inverted(ModuleConstants.kTurningEncoderInverted)
67+
self.turningConfig.absoluteEncoder.inverted(
68+
ModuleConstants.kTurningEncoderInverted
69+
)
6870

6971
# Enable PID wrap around for the turning motor. This will allow the PID
7072
# controller to go through 0 to get to the setpoint i.e. going from 350 degrees
@@ -104,8 +106,16 @@ def __init__(
104106

105107
# Save the SPARK MAX configurations. If a SPARK MAX browns out during
106108
# operation, it will maintain the above configurations.
107-
self.drivingSparkMax.configure(self.drivingConfig, SparkBase.ResetMode.kResetSafeParameters, SparkBase.PersistMode.kPersistParameters)
108-
self.turningSparkMax.configure(self.turningConfig, SparkBase.ResetMode.kResetSafeParameters, SparkBase.PersistMode.kPersistParameters)
109+
self.drivingSparkMax.configure(
110+
self.drivingConfig,
111+
SparkBase.ResetMode.kResetSafeParameters,
112+
SparkBase.PersistMode.kPersistParameters
113+
)
114+
self.turningSparkMax.configure(
115+
self.turningConfig,
116+
SparkBase.ResetMode.kResetSafeParameters,
117+
SparkBase.PersistMode.kPersistParameters
118+
)
109119

110120
self.chassisAngularOffset = chassisAngularOffset
111121
self.desiredState.angle = Rotation2d(self.turningEncoder.getPosition())

0 commit comments

Comments
 (0)