8
8
import edu .wpi .first .math .kinematics .SwerveModulePosition ;
9
9
import edu .wpi .first .math .kinematics .SwerveModuleState ;
10
10
11
- import com .revrobotics .CANSparkMax ;
12
- import com .revrobotics .CANSparkLowLevel .MotorType ;
13
- import com .revrobotics .SparkAbsoluteEncoder .Type ;
14
- import com .revrobotics .SparkPIDController ;
11
+ import com .revrobotics .spark .SparkClosedLoopController ;
12
+ import com .revrobotics .spark .SparkMax ;
13
+ import com .revrobotics .spark .SparkBase .ControlType ;
14
+ import com .revrobotics .spark .SparkBase .PersistMode ;
15
+ import com .revrobotics .spark .SparkBase .ResetMode ;
16
+ import com .revrobotics .spark .SparkLowLevel .MotorType ;
15
17
import com .revrobotics .AbsoluteEncoder ;
16
18
import com .revrobotics .RelativeEncoder ;
17
19
18
- import frc .robot .Constants . ModuleConstants ;
20
+ import frc .robot .Configs ;
19
21
20
22
public class MAXSwerveModule {
21
- private final CANSparkMax m_drivingSparkMax ;
22
- private final CANSparkMax m_turningSparkMax ;
23
+ private final SparkMax m_drivingSparkMax ;
24
+ private final SparkMax m_turningSparkMax ;
23
25
24
26
private final RelativeEncoder m_drivingEncoder ;
25
27
private final AbsoluteEncoder m_turningEncoder ;
26
28
27
- private final SparkPIDController m_drivingPIDController ;
28
- private final SparkPIDController m_turningPIDController ;
29
+ private final SparkClosedLoopController m_drivingPIDController ;
30
+ private final SparkClosedLoopController m_turningPIDController ;
29
31
30
32
private double m_chassisAngularOffset = 0 ;
31
33
private SwerveModuleState m_desiredState = new SwerveModuleState (0.0 , new Rotation2d ());
@@ -37,73 +39,22 @@ public class MAXSwerveModule {
37
39
* Encoder.
38
40
*/
39
41
public MAXSwerveModule (int drivingCANId , int turningCANId , double chassisAngularOffset ) {
40
- m_drivingSparkMax = new CANSparkMax (drivingCANId , MotorType .kBrushless );
41
- m_turningSparkMax = new CANSparkMax (turningCANId , MotorType .kBrushless );
42
+ m_drivingSparkMax = new SparkMax (drivingCANId , MotorType .kBrushless );
43
+ m_turningSparkMax = new SparkMax (turningCANId , MotorType .kBrushless );
42
44
43
- // Factory reset, so we get the SPARKS MAX to a known state before configuring
44
- // them. This is useful in case a SPARK MAX is swapped out.
45
- m_drivingSparkMax .restoreFactoryDefaults ();
46
- m_turningSparkMax .restoreFactoryDefaults ();
47
-
48
- // Setup encoders and PID controllers for the driving and turning SPARKS MAX.
49
45
m_drivingEncoder = m_drivingSparkMax .getEncoder ();
50
- m_turningEncoder = m_turningSparkMax .getAbsoluteEncoder (Type .kDutyCycle );
51
- m_drivingPIDController = m_drivingSparkMax .getPIDController ();
52
- m_turningPIDController = m_turningSparkMax .getPIDController ();
53
- m_drivingPIDController .setFeedbackDevice (m_drivingEncoder );
54
- m_turningPIDController .setFeedbackDevice (m_turningEncoder );
55
-
56
- // Apply position and velocity conversion factors for the driving encoder. The
57
- // native units for position and velocity are rotations and RPM, respectively,
58
- // but we want meters and meters per second to use with WPILib's swerve APIs.
59
- m_drivingEncoder .setPositionConversionFactor (ModuleConstants .kDrivingEncoderPositionFactor );
60
- m_drivingEncoder .setVelocityConversionFactor (ModuleConstants .kDrivingEncoderVelocityFactor );
61
-
62
- // Apply position and velocity conversion factors for the turning encoder. We
63
- // want these in radians and radians per second to use with WPILib's swerve
64
- // APIs.
65
- m_turningEncoder .setPositionConversionFactor (ModuleConstants .kTurningEncoderPositionFactor );
66
- m_turningEncoder .setVelocityConversionFactor (ModuleConstants .kTurningEncoderVelocityFactor );
67
-
68
- // Invert the turning encoder, since the output shaft rotates in the opposite direction of
69
- // the steering motor in the MAXSwerve Module.
70
- m_turningEncoder .setInverted (ModuleConstants .kTurningEncoderInverted );
71
-
72
- // Enable PID wrap around for the turning motor. This will allow the PID
73
- // controller to go through 0 to get to the setpoint i.e. going from 350 degrees
74
- // to 10 degrees will go through 0 rather than the other direction which is a
75
- // longer route.
76
- m_turningPIDController .setPositionPIDWrappingEnabled (true );
77
- m_turningPIDController .setPositionPIDWrappingMinInput (ModuleConstants .kTurningEncoderPositionPIDMinInput );
78
- m_turningPIDController .setPositionPIDWrappingMaxInput (ModuleConstants .kTurningEncoderPositionPIDMaxInput );
79
-
80
- // Set the PID gains for the driving motor. Note these are example gains, and you
81
- // may need to tune them for your own robot!
82
- m_drivingPIDController .setP (ModuleConstants .kDrivingP );
83
- m_drivingPIDController .setI (ModuleConstants .kDrivingI );
84
- m_drivingPIDController .setD (ModuleConstants .kDrivingD );
85
- m_drivingPIDController .setFF (ModuleConstants .kDrivingFF );
86
- m_drivingPIDController .setOutputRange (ModuleConstants .kDrivingMinOutput ,
87
- ModuleConstants .kDrivingMaxOutput );
88
-
89
- // Set the PID gains for the turning motor. Note these are example gains, and you
90
- // may need to tune them for your own robot!
91
- m_turningPIDController .setP (ModuleConstants .kTurningP );
92
- m_turningPIDController .setI (ModuleConstants .kTurningI );
93
- m_turningPIDController .setD (ModuleConstants .kTurningD );
94
- m_turningPIDController .setFF (ModuleConstants .kTurningFF );
95
- m_turningPIDController .setOutputRange (ModuleConstants .kTurningMinOutput ,
96
- ModuleConstants .kTurningMaxOutput );
97
-
98
- m_drivingSparkMax .setIdleMode (ModuleConstants .kDrivingMotorIdleMode );
99
- m_turningSparkMax .setIdleMode (ModuleConstants .kTurningMotorIdleMode );
100
- m_drivingSparkMax .setSmartCurrentLimit (ModuleConstants .kDrivingMotorCurrentLimit );
101
- m_turningSparkMax .setSmartCurrentLimit (ModuleConstants .kTurningMotorCurrentLimit );
102
-
103
- // Save the SPARK MAX configurations. If a SPARK MAX browns out during
104
- // operation, it will maintain the above configurations.
105
- m_drivingSparkMax .burnFlash ();
106
- m_turningSparkMax .burnFlash ();
46
+ m_turningEncoder = m_turningSparkMax .getAbsoluteEncoder ();
47
+
48
+ m_drivingPIDController = m_drivingSparkMax .getClosedLoopController ();
49
+ m_turningPIDController = m_turningSparkMax .getClosedLoopController ();
50
+
51
+ // Apply the respective configurations to the SPARKS. Reset parameters before
52
+ // applying the configuration to bring the SPARK to a known good state. Persist
53
+ // the settings to the SPARK to avoid losing them on a power cycle.
54
+ m_drivingSparkMax .configure (Configs .MAXSwerveModule .drivingConfig , ResetMode .kResetSafeParameters ,
55
+ PersistMode .kPersistParameters );
56
+ m_turningSparkMax .configure (Configs .MAXSwerveModule .turningConfig , ResetMode .kResetSafeParameters ,
57
+ PersistMode .kPersistParameters );
107
58
108
59
m_chassisAngularOffset = chassisAngularOffset ;
109
60
m_desiredState .angle = new Rotation2d (m_turningEncoder .getPosition ());
@@ -151,8 +102,8 @@ public void setDesiredState(SwerveModuleState desiredState) {
151
102
new Rotation2d (m_turningEncoder .getPosition ()));
152
103
153
104
// Command driving and turning SPARKS MAX towards their respective setpoints.
154
- m_drivingPIDController .setReference (optimizedDesiredState .speedMetersPerSecond , CANSparkMax . ControlType .kVelocity );
155
- m_turningPIDController .setReference (optimizedDesiredState .angle .getRadians (), CANSparkMax . ControlType .kPosition );
105
+ m_drivingPIDController .setReference (optimizedDesiredState .speedMetersPerSecond , ControlType .kVelocity );
106
+ m_turningPIDController .setReference (optimizedDesiredState .angle .getRadians (), ControlType .kPosition );
156
107
157
108
m_desiredState = desiredState ;
158
109
}
0 commit comments