Skip to content
This repository was archived by the owner on May 19, 2024. It is now read-only.

Commit 8e8fbff

Browse files
committed
refactor(config): Rename tolerances.
1 parent 78c543c commit 8e8fbff

File tree

2 files changed

+18
-24
lines changed

2 files changed

+18
-24
lines changed

Diff for: src/main/java/frc/lib/config/FeedbackControllerConfig.java

+17-23
Original file line numberDiff line numberDiff line change
@@ -5,20 +5,15 @@
55

66
/** Feedback controller config. */
77
public record FeedbackControllerConfig(
8-
double kP,
9-
double kI,
10-
double kD,
11-
boolean continuous,
12-
double positionTolerance,
13-
double velocityTolerance) {
8+
double kP, double kI, double kD, boolean continuous, double tolerance, double rateTolerance) {
149

1510
public FeedbackControllerConfig {
1611
Objects.requireNonNull(kP);
1712
Objects.requireNonNull(kI);
1813
Objects.requireNonNull(kD);
1914
Objects.requireNonNull(continuous);
20-
Objects.requireNonNull(positionTolerance);
21-
Objects.requireNonNull(velocityTolerance);
15+
Objects.requireNonNull(tolerance);
16+
Objects.requireNonNull(rateTolerance);
2217
}
2318

2419
public static final class FeedbackControllerConfigBuilder {
@@ -30,9 +25,9 @@ public static final class FeedbackControllerConfigBuilder {
3025

3126
private boolean continuous;
3227

33-
private double positionTolerance;
28+
private double tolerance;
3429

35-
private double velocityTolerance;
30+
private double rateTolerance;
3631

3732
public static FeedbackControllerConfigBuilder defaults() {
3833
return new FeedbackControllerConfigBuilder(0.0, 0.0, 0.0, false, 0.0, 0.0);
@@ -45,23 +40,23 @@ public static FeedbackControllerConfigBuilder from(
4540
feedbackControllerConfig.kI,
4641
feedbackControllerConfig.kD,
4742
feedbackControllerConfig.continuous,
48-
feedbackControllerConfig.positionTolerance,
49-
feedbackControllerConfig.velocityTolerance);
43+
feedbackControllerConfig.tolerance,
44+
feedbackControllerConfig.rateTolerance);
5045
}
5146

5247
private FeedbackControllerConfigBuilder(
5348
double kP,
5449
double kI,
5550
double kD,
5651
boolean continuous,
57-
double positionTolerance,
58-
double velocityTolerance) {
52+
double tolerance,
53+
double rateTolerance) {
5954
this.kP = kP;
6055
this.kI = kI;
6156
this.kD = kD;
6257
this.continuous = continuous;
63-
this.positionTolerance = positionTolerance;
64-
this.velocityTolerance = velocityTolerance;
58+
this.tolerance = tolerance;
59+
this.rateTolerance = rateTolerance;
6560
}
6661

6762
public FeedbackControllerConfigBuilder kP(double kP) {
@@ -84,19 +79,18 @@ public FeedbackControllerConfigBuilder continuous(boolean continuous) {
8479
return this;
8580
}
8681

87-
public FeedbackControllerConfigBuilder positionTolerance(double positionTolerance) {
88-
this.positionTolerance = positionTolerance;
82+
public FeedbackControllerConfigBuilder tolerance(double tolerance) {
83+
this.tolerance = tolerance;
8984
return this;
9085
}
9186

92-
public FeedbackControllerConfigBuilder velocityTolerance(double velocityTolerance) {
93-
this.velocityTolerance = velocityTolerance;
87+
public FeedbackControllerConfigBuilder rateTolerance(double rateTolerance) {
88+
this.rateTolerance = rateTolerance;
9489
return this;
9590
}
9691

9792
public FeedbackControllerConfig build() {
98-
return new FeedbackControllerConfig(
99-
kP, kI, kD, continuous, positionTolerance, velocityTolerance);
93+
return new FeedbackControllerConfig(kP, kI, kD, continuous, tolerance, rateTolerance);
10094
}
10195
}
10296

@@ -108,7 +102,7 @@ public FeedbackControllerConfig build() {
108102
public PIDController createPIDController() {
109103
final PIDController pidController = new PIDController(kP, kI, kD);
110104

111-
pidController.setTolerance(positionTolerance, velocityTolerance);
105+
pidController.setTolerance(tolerance, rateTolerance);
112106

113107
if (continuous) {
114108
pidController.enableContinuousInput(-0.5, 0.5);

Diff for: src/main/java/frc/robot/swerve/Swerve.java

+1-1
Original file line numberDiff line numberDiff line change
@@ -48,7 +48,7 @@ public class Swerve extends Subsystem {
4848
.continuous(true)
4949
.kP(54.0)
5050
.kD(0.16)
51-
.positionTolerance(Units.degreesToRotations(1.0)))
51+
.tolerance(Units.degreesToRotations(1.0)))
5252
.build();
5353

5454
/** Drive motor config. */

0 commit comments

Comments
 (0)