Skip to content

Commit ab9062b

Browse files
committed
Use new configuration mechanism from REVLib 2025
1 parent ab3daea commit ab9062b

File tree

4 files changed

+96
-125
lines changed

4 files changed

+96
-125
lines changed
Lines changed: 56 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,56 @@
1+
package frc.robot;
2+
3+
import com.revrobotics.spark.config.SparkMaxConfig;
4+
import com.revrobotics.spark.config.ClosedLoopConfig.FeedbackSensor;
5+
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;
6+
7+
import frc.robot.Constants.ModuleConstants;
8+
9+
public final class Configs {
10+
public static final class MAXSwerveModule {
11+
public static final SparkMaxConfig drivingConfig = new SparkMaxConfig();
12+
public static final SparkMaxConfig turningConfig = new SparkMaxConfig();
13+
14+
static {
15+
// Use module constants to calculate conversion factors and feed forward gain.
16+
double drivingFactor = ModuleConstants.kWheelDiameterMeters * Math.PI
17+
/ ModuleConstants.kDrivingMotorReduction;
18+
double turningFactor = 2 * Math.PI;
19+
double drivingVelocityFeedForward = 1 / ModuleConstants.kDriveWheelFreeSpeedRps;
20+
21+
drivingConfig
22+
.idleMode(IdleMode.kBrake)
23+
.smartCurrentLimit(50);
24+
drivingConfig.encoder
25+
.positionConversionFactor(drivingFactor) // meters
26+
.velocityConversionFactor(drivingFactor / 60.0); // meters per second
27+
drivingConfig.closedLoop
28+
.feedbackSensor(FeedbackSensor.kPrimaryEncoder)
29+
// These are example gains you may need to them for your own robot!
30+
.pid(0.04, 0, 0)
31+
.velocityFF(drivingVelocityFeedForward)
32+
.outputRange(-1, 1);
33+
34+
turningConfig
35+
.idleMode(IdleMode.kBrake)
36+
.smartCurrentLimit(20);
37+
turningConfig.absoluteEncoder
38+
// Invert the turning encoder, since the output shaft rotates in the opposite
39+
// direction of the steering motor in the MAXSwerve Module.
40+
.inverted(true)
41+
.positionConversionFactor(turningFactor) // radians
42+
.velocityConversionFactor(turningFactor / 60.0); // radians per second
43+
turningConfig.closedLoop
44+
.feedbackSensor(FeedbackSensor.kAbsoluteEncoder)
45+
// These are example gains you may need to them for your own robot!
46+
.pid(1, 0, 0)
47+
.outputRange(-1, 1)
48+
// Enable PID wrap around for the turning motor. This will allow the PID
49+
// controller to go through 0 to get to the setpoint i.e. going from 350 degrees
50+
// to 10 degrees will go through 0 rather than the other direction which is a
51+
// longer route.
52+
.positionWrappingEnabled(true)
53+
.positionWrappingInputRange(0, turningFactor);
54+
}
55+
}
56+
}

src/main/java/frc/robot/Constants.java

Lines changed: 5 additions & 41 deletions
Original file line numberDiff line numberDiff line change
@@ -4,8 +4,6 @@
44

55
package frc.robot;
66

7-
import com.revrobotics.CANSparkBase.IdleMode;
8-
97
import edu.wpi.first.math.geometry.Translation2d;
108
import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
119
import edu.wpi.first.math.trajectory.TrapezoidProfile;
@@ -66,54 +64,20 @@ public static final class DriveConstants {
6664
}
6765

6866
public static final class ModuleConstants {
69-
// The MAXSwerve module can be configured with one of three pinion gears: 12T, 13T, or 14T.
70-
// This changes the drive speed of the module (a pinion gear with more teeth will result in a
71-
// robot that drives faster).
67+
// The MAXSwerve module can be configured with one of three pinion gears: 12T,
68+
// 13T, or 14T. This changes the drive speed of the module (a pinion gear with
69+
// more teeth will result in a robot that drives faster).
7270
public static final int kDrivingMotorPinionTeeth = 14;
7371

74-
// Invert the turning encoder, since the output shaft rotates in the opposite direction of
75-
// the steering motor in the MAXSwerve Module.
76-
public static final boolean kTurningEncoderInverted = true;
77-
7872
// Calculations required for driving motor conversion factors and feed forward
7973
public static final double kDrivingMotorFreeSpeedRps = NeoMotorConstants.kFreeSpeedRpm / 60;
8074
public static final double kWheelDiameterMeters = 0.0762;
8175
public static final double kWheelCircumferenceMeters = kWheelDiameterMeters * Math.PI;
82-
// 45 teeth on the wheel's bevel gear, 22 teeth on the first-stage spur gear, 15 teeth on the bevel pinion
76+
// 45 teeth on the wheel's bevel gear, 22 teeth on the first-stage spur gear, 15
77+
// teeth on the bevel pinion
8378
public static final double kDrivingMotorReduction = (45.0 * 22) / (kDrivingMotorPinionTeeth * 15);
8479
public static final double kDriveWheelFreeSpeedRps = (kDrivingMotorFreeSpeedRps * kWheelCircumferenceMeters)
8580
/ kDrivingMotorReduction;
86-
87-
public static final double kDrivingEncoderPositionFactor = (kWheelDiameterMeters * Math.PI)
88-
/ kDrivingMotorReduction; // meters
89-
public static final double kDrivingEncoderVelocityFactor = ((kWheelDiameterMeters * Math.PI)
90-
/ kDrivingMotorReduction) / 60.0; // meters per second
91-
92-
public static final double kTurningEncoderPositionFactor = (2 * Math.PI); // radians
93-
public static final double kTurningEncoderVelocityFactor = (2 * Math.PI) / 60.0; // radians per second
94-
95-
public static final double kTurningEncoderPositionPIDMinInput = 0; // radians
96-
public static final double kTurningEncoderPositionPIDMaxInput = kTurningEncoderPositionFactor; // radians
97-
98-
public static final double kDrivingP = 0.04;
99-
public static final double kDrivingI = 0;
100-
public static final double kDrivingD = 0;
101-
public static final double kDrivingFF = 1 / kDriveWheelFreeSpeedRps;
102-
public static final double kDrivingMinOutput = -1;
103-
public static final double kDrivingMaxOutput = 1;
104-
105-
public static final double kTurningP = 1;
106-
public static final double kTurningI = 0;
107-
public static final double kTurningD = 0;
108-
public static final double kTurningFF = 0;
109-
public static final double kTurningMinOutput = -1;
110-
public static final double kTurningMaxOutput = 1;
111-
112-
public static final IdleMode kDrivingMotorIdleMode = IdleMode.kBrake;
113-
public static final IdleMode kTurningMotorIdleMode = IdleMode.kBrake;
114-
115-
public static final int kDrivingMotorCurrentLimit = 50; // amps
116-
public static final int kTurningMotorCurrentLimit = 20; // amps
11781
}
11882

11983
public static final class OIConstants {

src/main/java/frc/robot/subsystems/MAXSwerveModule.java

Lines changed: 27 additions & 76 deletions
Original file line numberDiff line numberDiff line change
@@ -8,24 +8,26 @@
88
import edu.wpi.first.math.kinematics.SwerveModulePosition;
99
import edu.wpi.first.math.kinematics.SwerveModuleState;
1010

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;
1517
import com.revrobotics.AbsoluteEncoder;
1618
import com.revrobotics.RelativeEncoder;
1719

18-
import frc.robot.Constants.ModuleConstants;
20+
import frc.robot.Configs;
1921

2022
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;
2325

2426
private final RelativeEncoder m_drivingEncoder;
2527
private final AbsoluteEncoder m_turningEncoder;
2628

27-
private final SparkPIDController m_drivingPIDController;
28-
private final SparkPIDController m_turningPIDController;
29+
private final SparkClosedLoopController m_drivingPIDController;
30+
private final SparkClosedLoopController m_turningPIDController;
2931

3032
private double m_chassisAngularOffset = 0;
3133
private SwerveModuleState m_desiredState = new SwerveModuleState(0.0, new Rotation2d());
@@ -37,73 +39,22 @@ public class MAXSwerveModule {
3739
* Encoder.
3840
*/
3941
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);
4244

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.
4945
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);
10758

10859
m_chassisAngularOffset = chassisAngularOffset;
10960
m_desiredState.angle = new Rotation2d(m_turningEncoder.getPosition());
@@ -151,8 +102,8 @@ public void setDesiredState(SwerveModuleState desiredState) {
151102
new Rotation2d(m_turningEncoder.getPosition()));
152103

153104
// 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);
156107

157108
m_desiredState = desiredState;
158109
}

vendordeps/REVLib.json renamed to vendordeps/REVLib-2025.0.0-beta-1.json

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -1,25 +1,25 @@
11
{
2-
"fileName": "REVLib.json",
2+
"fileName": "REVLib-2025.0.0-beta-1.json",
33
"name": "REVLib",
4-
"version": "2024.2.0",
5-
"frcYear": "2024",
4+
"version": "2025.0.0-beta-1",
5+
"frcYear": "2025",
66
"uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb",
77
"mavenUrls": [
88
"https://maven.revrobotics.com/"
99
],
10-
"jsonUrl": "https://software-metadata.revrobotics.com/REVLib-2024.json",
10+
"jsonUrl": "https://software-metadata.revrobotics.com/REVLib-2025.json",
1111
"javaDependencies": [
1212
{
1313
"groupId": "com.revrobotics.frc",
1414
"artifactId": "REVLib-java",
15-
"version": "2024.2.0"
15+
"version": "2025.0.0-beta-1"
1616
}
1717
],
1818
"jniDependencies": [
1919
{
2020
"groupId": "com.revrobotics.frc",
2121
"artifactId": "REVLib-driver",
22-
"version": "2024.2.0",
22+
"version": "2025.0.0-beta-1",
2323
"skipInvalidPlatforms": true,
2424
"isJar": false,
2525
"validPlatforms": [
@@ -37,7 +37,7 @@
3737
{
3838
"groupId": "com.revrobotics.frc",
3939
"artifactId": "REVLib-cpp",
40-
"version": "2024.2.0",
40+
"version": "2025.0.0-beta-1",
4141
"libName": "REVLib",
4242
"headerClassifier": "headers",
4343
"sharedLibrary": false,
@@ -55,7 +55,7 @@
5555
{
5656
"groupId": "com.revrobotics.frc",
5757
"artifactId": "REVLib-driver",
58-
"version": "2024.2.0",
58+
"version": "2025.0.0-beta-1",
5959
"libName": "REVLibDriver",
6060
"headerClassifier": "headers",
6161
"sharedLibrary": false,

0 commit comments

Comments
 (0)