44# the WPILib BSD license file in the root directory of this project.
55#
66
7- from rev import CANSparkMax , SparkMaxAbsoluteEncoder
7+ from rev import SparkMax , SparkMaxConfig , ClosedLoopConfig , SparkBase
88from wpimath .geometry import Rotation2d
99from wpimath .kinematics import SwerveModuleState , SwerveModulePosition
1010
@@ -24,97 +24,88 @@ def __init__(
2424 self .chassisAngularOffset = 0
2525 self .desiredState = SwerveModuleState (0.0 , Rotation2d ())
2626
27- self .drivingSparkMax = CANSparkMax (
28- drivingCANId , CANSparkMax .MotorType .kBrushless
27+ self .drivingSparkMax = SparkMax (
28+ drivingCANId , SparkMax .MotorType .kBrushless
2929 )
30- self .turningSparkMax = CANSparkMax (
31- turningCANId , CANSparkMax .MotorType .kBrushless
30+ self .turningSparkMax = SparkMax (
31+ turningCANId , SparkMax .MotorType .kBrushless
3232 )
3333
34- # Factory reset, so we get the SPARKS MAX to a known state before configuring
35- # them. This is useful in case a SPARK MAX is swapped out.
36- self .drivingSparkMax .restoreFactoryDefaults ()
37- self .turningSparkMax .restoreFactoryDefaults ()
34+ self .drivingConfig = SparkMaxConfig ()
35+ self .turningConfig = SparkMaxConfig ()
3836
3937 # Setup encoders and PID controllers for the driving and turning SPARKS MAX.
4038 self .drivingEncoder = self .drivingSparkMax .getEncoder ()
41- self .turningEncoder = self .turningSparkMax .getAbsoluteEncoder (
42- SparkMaxAbsoluteEncoder .Type .kDutyCycle
43- )
44- self .drivingPIDController = self .drivingSparkMax .getPIDController ()
45- self .turningPIDController = self .turningSparkMax .getPIDController ()
46- self .drivingPIDController .setFeedbackDevice (self .drivingEncoder )
47- self .turningPIDController .setFeedbackDevice (self .turningEncoder )
39+ self .turningEncoder = self .turningSparkMax .getAbsoluteEncoder ()
40+ self .drivingPidController = self .drivingSparkMax .getClosedLoopController ()
41+ self .turningPidController = self .turningSparkMax .getClosedLoopController ()
42+ self .drivingConfig .closedLoop .setFeedbackSensor (ClosedLoopConfig .FeedbackSensor .kPrimaryEncoder )
43+ self .turningConfig .closedLoop .setFeedbackSensor (ClosedLoopConfig .FeedbackSensor .kAbsoluteEncoder )
4844
4945 # Apply position and velocity conversion factors for the driving encoder. The
5046 # native units for position and velocity are rotations and RPM, respectively,
5147 # but we want meters and meters per second to use with WPILib's swerve APIs.
52- self .drivingEncoder . setPositionConversionFactor (
48+ self .drivingConfig . encoder . positionConversionFactor (
5349 ModuleConstants .kDrivingEncoderPositionFactor
5450 )
55- self .drivingEncoder . setVelocityConversionFactor (
51+ self .drivingConfig . encoder . velocityConversionFactor (
5652 ModuleConstants .kDrivingEncoderVelocityFactor
5753 )
5854
5955 # Apply position and velocity conversion factors for the turning encoder. We
6056 # want these in radians and radians per second to use with WPILib's swerve
6157 # APIs.
62- self .turningEncoder . setPositionConversionFactor (
58+ self .turningConfig . absoluteEncoder . positionConversionFactor (
6359 ModuleConstants .kTurningEncoderPositionFactor
6460 )
65- self .turningEncoder . setVelocityConversionFactor (
61+ self .turningConfig . absoluteEncoder . velocityConversionFactor (
6662 ModuleConstants .kTurningEncoderVelocityFactor
6763 )
6864
6965 # Invert the turning encoder, since the output shaft rotates in the opposite direction of
7066 # the steering motor in the MAXSwerve Module.
71- self .turningEncoder . setInverted (ModuleConstants .kTurningEncoderInverted )
67+ self .turningConfig . absoluteEncoder . inverted (ModuleConstants .kTurningEncoderInverted )
7268
7369 # Enable PID wrap around for the turning motor. This will allow the PID
7470 # controller to go through 0 to get to the setpoint i.e. going from 350 degrees
7571 # to 10 degrees will go through 0 rather than the other direction which is a
7672 # longer route.
77- self .turningPIDController . setPositionPIDWrappingEnabled (True )
78- self .turningPIDController . setPositionPIDWrappingMinInput (
73+ self .turningConfig . closedLoop . positionWrappingEnabled (True )
74+ self .turningConfig . closedLoop . positionWrappingMinInput (
7975 ModuleConstants .kTurningEncoderPositionPIDMinInput
8076 )
81- self .turningPIDController . setPositionPIDWrappingMaxInput (
77+ self .turningConfig . closedLoop . positionWrappingMaxInput (
8278 ModuleConstants .kTurningEncoderPositionPIDMaxInput
8379 )
8480
8581 # Set the PID gains for the driving motor. Note these are example gains, and you
8682 # may need to tune them for your own robot!
87- self .drivingPIDController . setP (ModuleConstants .kDrivingP )
88- self .drivingPIDController . setI (ModuleConstants .kDrivingI )
89- self .drivingPIDController . setD (ModuleConstants .kDrivingD )
90- self .drivingPIDController . setFF (ModuleConstants .kDrivingFF )
91- self .drivingPIDController . setOutputRange (
83+ self .drivingConfig . closedLoop . P (ModuleConstants .kDrivingP )
84+ self .drivingConfig . closedLoop . I (ModuleConstants .kDrivingI )
85+ self .drivingConfig . closedLoop . D (ModuleConstants .kDrivingD )
86+ self .drivingConfig . closedLoop . velocityFF (ModuleConstants .kDrivingFF )
87+ self .drivingConfig . closedLoop . outputRange (
9288 ModuleConstants .kDrivingMinOutput , ModuleConstants .kDrivingMaxOutput
9389 )
9490
9591 # Set the PID gains for the turning motor. Note these are example gains, and you
9692 # may need to tune them for your own robot!
97- self .turningPIDController . setP (ModuleConstants .kTurningP )
98- self .turningPIDController . setI (ModuleConstants .kTurningI )
99- self .turningPIDController . setD (ModuleConstants .kTurningD )
100- self .turningPIDController . setFF (ModuleConstants .kTurningFF )
101- self .turningPIDController . setOutputRange (
93+ self .turningConfig . closedLoop . P (ModuleConstants .kTurningP )
94+ self .turningConfig . closedLoop . I (ModuleConstants .kTurningI )
95+ self .turningConfig . closedLoop . D (ModuleConstants .kTurningD )
96+ self .turningConfig . closedLoop . velocityFF (ModuleConstants .kTurningFF )
97+ self .turningConfig . closedLoop . outputRange (
10298 ModuleConstants .kTurningMinOutput , ModuleConstants .kTurningMaxOutput
10399 )
104100
105- self .drivingSparkMax .setIdleMode (ModuleConstants .kDrivingMotorIdleMode )
106- self .turningSparkMax .setIdleMode (ModuleConstants .kTurningMotorIdleMode )
107- self .drivingSparkMax .setSmartCurrentLimit (
108- ModuleConstants .kDrivingMotorCurrentLimit
109- )
110- self .turningSparkMax .setSmartCurrentLimit (
111- ModuleConstants .kTurningMotorCurrentLimit
112- )
101+ self .drivingConfig .setIdleMode (ModuleConstants .kDrivingMotorIdleMode )
102+ self .turningConfig .setIdleMode (ModuleConstants .kTurningMotorIdleMode )
103+ # XXX -- can we set current limits?
113104
114105 # Save the SPARK MAX configurations. If a SPARK MAX browns out during
115106 # operation, it will maintain the above configurations.
116- self .drivingSparkMax .burnFlash ( )
117- self .turningSparkMax .burnFlash ( )
107+ self .drivingSparkMax .configure ( self . drivingConfig , SparkBase . ResetMode . kResetSafeParameters , SparkBase . PersistMode . kPersistParameters )
108+ self .turningSparkMax .configure ( self . turningConfig , SparkBase . ResetMode . kResetSafeParameters , SparkBase . PersistMode . kPersistParameters )
118109
119110 self .chassisAngularOffset = chassisAngularOffset
120111 self .desiredState .angle = Rotation2d (self .turningEncoder .getPosition ())
@@ -158,16 +149,16 @@ def setDesiredState(self, desiredState: SwerveModuleState) -> None:
158149 )
159150
160151 # Optimize the reference state to avoid spinning further than 90 degrees.
161- optimizedDesiredState = SwerveModuleState .optimize (
152+ SwerveModuleState .optimize (
162153 correctedDesiredState , Rotation2d (self .turningEncoder .getPosition ())
163154 )
164155
165156 # Command driving and turning SPARKS MAX towards their respective setpoints.
166- self .drivingPIDController .setReference (
167- optimizedDesiredState .speed , CANSparkMax .ControlType .kVelocity
157+ self .drivingPidController .setReference (
158+ correctedDesiredState .speed , SparkMax .ControlType .kVelocity
168159 )
169- self .turningPIDController .setReference (
170- optimizedDesiredState .angle .radians (), CANSparkMax .ControlType .kPosition
160+ self .turningPidController .setReference (
161+ correctedDesiredState .angle .radians (), SparkMax .ControlType .kPosition
171162 )
172163
173164 self .desiredState = desiredState
0 commit comments