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

Commit 4a21d0c

Browse files
committed
refactor(config): Use method calls for values.
1 parent ae6219e commit 4a21d0c

11 files changed

+103
-59
lines changed

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

+50-12
Original file line numberDiff line numberDiff line change
@@ -4,25 +4,26 @@
44
public class MechanismConfig {
55

66
/** Absolute encoder config. */
7-
public AbsoluteEncoderConfig absoluteEncoder = new AbsoluteEncoderConfig();
7+
private AbsoluteEncoderConfig absoluteEncoderConfig = new AbsoluteEncoderConfig();
88

99
/** Feedback controller config. */
10-
public FeedbackControllerConfig feedback = new FeedbackControllerConfig();
10+
private FeedbackControllerConfig feedbackControllerConfig = new FeedbackControllerConfig();
1111

1212
/** Feedforward controller config. */
13-
public FeedforwardControllerConfig feedforward = new FeedforwardControllerConfig();
13+
private FeedforwardControllerConfig feedforwardControllerConfig =
14+
new FeedforwardControllerConfig();
1415

1516
/** Motor config. */
16-
public MotorConfig motor = new MotorConfig();
17+
private MotorConfig motorConfig = new MotorConfig();
1718

1819
/**
1920
* Modifies this mechanism config to use the absolute encoder config.
2021
*
2122
* @param absoluteEncoderConfig the absolute encoder config.
2223
* @return this mechanism config.
2324
*/
24-
public MechanismConfig withAbsoluteEncoder(AbsoluteEncoderConfig absoluteEncoderConfig) {
25-
this.absoluteEncoder = absoluteEncoderConfig;
25+
public MechanismConfig withAbsoluteEncoderConfig(AbsoluteEncoderConfig absoluteEncoderConfig) {
26+
this.absoluteEncoderConfig = absoluteEncoderConfig;
2627
return this;
2728
}
2829

@@ -32,8 +33,8 @@ public MechanismConfig withAbsoluteEncoder(AbsoluteEncoderConfig absoluteEncoder
3233
* @param feedbackControllerConfig the feedback controller config.
3334
* @return this mechanism config.
3435
*/
35-
public MechanismConfig withFeedback(FeedbackControllerConfig feedbackControllerConfig) {
36-
this.feedback = feedbackControllerConfig;
36+
public MechanismConfig withFeedbackConfig(FeedbackControllerConfig feedbackControllerConfig) {
37+
this.feedbackControllerConfig = feedbackControllerConfig;
3738
return this;
3839
}
3940

@@ -43,8 +44,9 @@ public MechanismConfig withFeedback(FeedbackControllerConfig feedbackControllerC
4344
* @param feedforwardControllerConfig the feedforward controller config.
4445
* @return this mechanism config.
4546
*/
46-
public MechanismConfig withFeedforward(FeedforwardControllerConfig feedforwardControllerConfig) {
47-
this.feedforward = feedforwardControllerConfig;
47+
public MechanismConfig withFeedforwardConfig(
48+
FeedforwardControllerConfig feedforwardControllerConfig) {
49+
this.feedforwardControllerConfig = feedforwardControllerConfig;
4850
return this;
4951
}
5052

@@ -54,8 +56,44 @@ public MechanismConfig withFeedforward(FeedforwardControllerConfig feedforwardCo
5456
* @param motorConfig the motor config.
5557
* @return this mechanism config.
5658
*/
57-
public MechanismConfig withMotor(MotorConfig motorConfig) {
58-
this.motor = motorConfig;
59+
public MechanismConfig withMotorConfig(MotorConfig motorConfig) {
60+
this.motorConfig = motorConfig;
5961
return this;
6062
}
63+
64+
/**
65+
* Returns the absolute encoder config.
66+
*
67+
* @return the absolute encoder config.
68+
*/
69+
public AbsoluteEncoderConfig absoluteEncoderConfig() {
70+
return absoluteEncoderConfig;
71+
}
72+
73+
/**
74+
* Returns the feedback controller config.
75+
*
76+
* @return the feedback controller config.
77+
*/
78+
public FeedbackControllerConfig feedbackControllerConfig() {
79+
return feedbackControllerConfig;
80+
}
81+
82+
/**
83+
* Returns the feedforward controller config.
84+
*
85+
* @return the feedforward controller config.
86+
*/
87+
public FeedforwardControllerConfig feedforwardControllerConfig() {
88+
return feedforwardControllerConfig;
89+
}
90+
91+
/**
92+
* Returns the motor config.
93+
*
94+
* @return the motor config.
95+
*/
96+
public MotorConfig motorConfig() {
97+
return motorConfig;
98+
}
6199
}

Diff for: src/main/java/frc/lib/controller/PositionControllerIOTalonFX2.java

+12-10
Original file line numberDiff line numberDiff line change
@@ -69,9 +69,9 @@ public PositionControllerIOTalonFX2(
6969
volts = leaderMotor.getMotorVoltage();
7070
amps = leaderMotor.getStatorCurrent();
7171

72-
feedforward = config.feedforward.createArmFeedforward();
72+
feedforward = config.feedforwardControllerConfig().createArmFeedforward();
7373

74-
feedback = config.feedback.createPIDController();
74+
feedback = config.feedbackControllerConfig().createPIDController();
7575

7676
followerMotor.setControl(new Follower(leaderMotor.getDeviceID(), invertFollower));
7777

@@ -87,34 +87,36 @@ public void configure() {
8787
TalonFXConfiguration motorConfig = new TalonFXConfiguration();
8888

8989
motorConfig.MotorOutput.Inverted =
90-
config.motor.ccwPositive()
90+
config.motorConfig().ccwPositive()
9191
? InvertedValue.CounterClockwise_Positive
9292
: InvertedValue.Clockwise_Positive;
9393
motorConfig.MotorOutput.NeutralMode =
94-
config.motor.neutralBrake() ? NeutralModeValue.Brake : NeutralModeValue.Coast;
94+
config.motorConfig().neutralBrake() ? NeutralModeValue.Brake : NeutralModeValue.Coast;
9595

9696
// Stator current is a measure of the current inside of the motor and is typically higher than
9797
// supply (breaker) current
98-
motorConfig.CurrentLimits.StatorCurrentLimit = config.motor.currentLimitAmps() * 2.0;
98+
motorConfig.CurrentLimits.StatorCurrentLimit = config.motorConfig().currentLimitAmps() * 2.0;
9999
motorConfig.CurrentLimits.StatorCurrentLimitEnable = true;
100100

101-
motorConfig.CurrentLimits.SupplyCurrentLimit = config.motor.currentLimitAmps();
101+
motorConfig.CurrentLimits.SupplyCurrentLimit = config.motorConfig().currentLimitAmps();
102102
// Allow higher current spikes (150%) for a brief duration (one second)
103103
// REV 40A auto-resetting breakers typically trip when current exceeds 300% for one second
104-
motorConfig.CurrentLimits.SupplyCurrentThreshold = config.motor.currentLimitAmps() * 1.5;
104+
motorConfig.CurrentLimits.SupplyCurrentThreshold =
105+
config.motorConfig().currentLimitAmps() * 1.5;
105106
motorConfig.CurrentLimits.SupplyTimeThreshold = 1;
106107
motorConfig.CurrentLimits.SupplyCurrentLimitEnable = true;
107108

108-
motorConfig.Feedback.SensorToMechanismRatio = config.motor.motorToMechanismRatio();
109+
motorConfig.Feedback.SensorToMechanismRatio = config.motorConfig().motorToMechanismRatio();
109110

110111
Configurator.configureTalonFX(leaderMotor.getConfigurator(), motorConfig);
111112
Configurator.configureTalonFX(followerMotor.getConfigurator(), motorConfig);
112113

113114
CANcoderConfiguration encoderConfig = new CANcoderConfiguration();
114115

115-
encoderConfig.MagnetSensor.MagnetOffset = config.absoluteEncoder.offset().getRotations();
116+
encoderConfig.MagnetSensor.MagnetOffset =
117+
config.absoluteEncoderConfig().offset().getRotations();
116118
encoderConfig.MagnetSensor.SensorDirection =
117-
config.absoluteEncoder.ccwPositive()
119+
config.absoluteEncoderConfig().ccwPositive()
118120
? SensorDirectionValue.CounterClockwise_Positive
119121
: SensorDirectionValue.Clockwise_Positive;
120122

Diff for: src/main/java/frc/lib/controller/VelocityControllerIOTalonFX.java

+7-6
Original file line numberDiff line numberDiff line change
@@ -45,25 +45,26 @@ public void configure() {
4545
TalonFXConfiguration motorConfig = new TalonFXConfiguration();
4646

4747
motorConfig.MotorOutput.Inverted =
48-
config.motor.ccwPositive()
48+
config.motorConfig().ccwPositive()
4949
? InvertedValue.CounterClockwise_Positive
5050
: InvertedValue.Clockwise_Positive;
5151
motorConfig.MotorOutput.NeutralMode =
52-
config.motor.neutralBrake() ? NeutralModeValue.Brake : NeutralModeValue.Coast;
52+
config.motorConfig().neutralBrake() ? NeutralModeValue.Brake : NeutralModeValue.Coast;
5353

5454
// Stator current is a measure of the current inside of the motor and is typically higher than
5555
// supply (breaker) current
56-
motorConfig.CurrentLimits.StatorCurrentLimit = config.motor.currentLimitAmps() * 2.0;
56+
motorConfig.CurrentLimits.StatorCurrentLimit = config.motorConfig().currentLimitAmps() * 2.0;
5757
motorConfig.CurrentLimits.StatorCurrentLimitEnable = true;
5858

59-
motorConfig.CurrentLimits.SupplyCurrentLimit = config.motor.currentLimitAmps();
59+
motorConfig.CurrentLimits.SupplyCurrentLimit = config.motorConfig().currentLimitAmps();
6060
// Allow higher current spikes (150%) for a brief duration (one second)
6161
// REV 40A auto-resetting breakers typically trip when current exceeds 300% for one second
62-
motorConfig.CurrentLimits.SupplyCurrentThreshold = config.motor.currentLimitAmps() * 1.5;
62+
motorConfig.CurrentLimits.SupplyCurrentThreshold =
63+
config.motorConfig().currentLimitAmps() * 1.5;
6364
motorConfig.CurrentLimits.SupplyTimeThreshold = 1;
6465
motorConfig.CurrentLimits.SupplyCurrentLimitEnable = true;
6566

66-
motorConfig.Feedback.SensorToMechanismRatio = config.motor.motorToMechanismRatio();
67+
motorConfig.Feedback.SensorToMechanismRatio = config.motorConfig().motorToMechanismRatio();
6768

6869
Configurator.configureTalonFX(motor.getConfigurator(), motorConfig);
6970
}

Diff for: src/main/java/frc/lib/controller/VelocityControllerIOTalonFXPIDF.java

+2-2
Original file line numberDiff line numberDiff line change
@@ -25,9 +25,9 @@ public class VelocityControllerIOTalonFXPIDF extends VelocityControllerIOTalonFX
2525
public VelocityControllerIOTalonFXPIDF(CAN can, MechanismConfig config, boolean enableFOC) {
2626
super(can, config);
2727

28-
feedforward = config.feedforward.createSimpleMotorFeedforward();
28+
feedforward = config.feedforwardControllerConfig().createSimpleMotorFeedforward();
2929

30-
feedback = config.feedback.createPIDController();
30+
feedback = config.feedbackControllerConfig().createPIDController();
3131

3232
voltage = new VoltageOut(0.0).withEnableFOC(enableFOC);
3333
}

Diff for: src/main/java/frc/robot/arm/ArmConstants.java

+4-4
Original file line numberDiff line numberDiff line change
@@ -27,22 +27,22 @@ public static class ShoulderConstants {
2727
/** Shoulder's config. */
2828
public static final MechanismConfig CONFIG =
2929
new MechanismConfig()
30-
.withAbsoluteEncoder(
30+
.withAbsoluteEncoderConfig(
3131
new AbsoluteEncoderConfig()
3232
.withCCWPositive(false)
3333
.withOffset(Rotation2d.fromDegrees(-173.135)))
34-
.withMotor(
34+
.withMotorConfig(
3535
new MotorConfig()
3636
.withCCWPositive(true)
3737
.withNeutralBrake(true)
3838
.withMotorToMechanismRatio(39.771428571))
39-
.withFeedforward(
39+
.withFeedforwardConfig(
4040
new FeedforwardControllerConfig()
4141
.withStaticFeedforward(0.14) // volts
4242
.withGravityFeedforward(0.5125) // volts
4343
.withVelocityFeedforward(4.0) // volts per rotation per second
4444
)
45-
.withFeedback(
45+
.withFeedbackConfig(
4646
new FeedbackControllerConfig().withProportionalGain(4.0) // volts per rotation
4747
);
4848

Diff for: src/main/java/frc/robot/intake/IntakeConstants.java

+6-6
Original file line numberDiff line numberDiff line change
@@ -16,17 +16,17 @@ public static class FrontRollerConstants {
1616
/** Front roller's config. */
1717
public static final MechanismConfig CONFIG =
1818
new MechanismConfig()
19-
.withMotor(
19+
.withMotorConfig(
2020
new MotorConfig()
2121
.withCCWPositive(false)
2222
.withNeutralBrake(false)
2323
.withMotorToMechanismRatio(24.0 / 16.0))
24-
.withFeedforward(
24+
.withFeedforwardConfig(
2525
new FeedforwardControllerConfig()
2626
.withStaticFeedforward(0.13) // volts
2727
.withVelocityFeedforward(0.1683) // volts per rotation per second
2828
)
29-
.withFeedback(
29+
.withFeedbackConfig(
3030
new FeedbackControllerConfig()
3131
.withProportionalGain(0.1) // volts per rotation per second
3232
);
@@ -48,17 +48,17 @@ public static class BackRollerConstants {
4848

4949
public static final MechanismConfig CONFIG =
5050
new MechanismConfig()
51-
.withMotor(
51+
.withMotorConfig(
5252
new MotorConfig()
5353
.withCCWPositive(false)
5454
.withNeutralBrake(false)
5555
.withMotorToMechanismRatio(24.0 / 16.0))
56-
.withFeedforward(
56+
.withFeedforwardConfig(
5757
new FeedforwardControllerConfig()
5858
.withStaticFeedforward(0.13) // volts
5959
.withVelocityFeedforward(0.1759) // volts per rotation per second
6060
)
61-
.withFeedback(
61+
.withFeedbackConfig(
6262
new FeedbackControllerConfig()
6363
.withProportionalGain(0.1) // volts per rotation per second
6464
);

Diff for: src/main/java/frc/robot/shooter/ShooterConstants.java

+5-5
Original file line numberDiff line numberDiff line change
@@ -19,12 +19,12 @@ public static class SerializerConstants {
1919
/** Serializer's config. */
2020
public static final MechanismConfig PIDF_CONTROLLER_CONSTANTS =
2121
new MechanismConfig()
22-
.withMotor(
22+
.withMotorConfig(
2323
new MotorConfig()
2424
.withCCWPositive(true)
2525
.withNeutralBrake(false)
2626
.withMotorToMechanismRatio(36.0 / 16.0))
27-
.withFeedforward(
27+
.withFeedforwardConfig(
2828
new FeedforwardControllerConfig()
2929
.withStaticFeedforward(0.14) // volts
3030
.withVelocityFeedforward(0.2617) // volts per rotation per second
@@ -59,17 +59,17 @@ public static class FlywheelConstants {
5959
/** Flywheel's config. */
6060
public static final MechanismConfig CONFIG =
6161
new MechanismConfig()
62-
.withMotor(
62+
.withMotorConfig(
6363
new MotorConfig()
6464
.withCCWPositive(false)
6565
.withNeutralBrake(true)
6666
.withMotorToMechanismRatio(28.0 / 16.0))
67-
.withFeedforward(
67+
.withFeedforwardConfig(
6868
new FeedforwardControllerConfig()
6969
.withStaticFeedforward(0.14) // volts
7070
.withVelocityFeedforward(0.2) // volts per rotation per second
7171
)
72-
.withFeedback(
72+
.withFeedbackConfig(
7373
new FeedbackControllerConfig()
7474
.withProportionalGain(0.14) // volts per rotation per second
7575
);

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

+5-2
Original file line numberDiff line numberDiff line change
@@ -30,9 +30,12 @@ public DriveMotorIOTalonFXPID(CAN can) {
3030
super(can);
3131

3232
velocityFeedforward =
33-
SwerveConstants.DRIVE_PIDF_CONSTANTS.feedforward.createSimpleMotorFeedforward();
33+
SwerveConstants.DRIVE_PIDF_CONSTANTS
34+
.feedforwardControllerConfig()
35+
.createSimpleMotorFeedforward();
3436

35-
velocityFeedback = SwerveConstants.DRIVE_PIDF_CONSTANTS.feedback.createPIDController();
37+
velocityFeedback =
38+
SwerveConstants.DRIVE_PIDF_CONSTANTS.feedbackControllerConfig().createPIDController();
3639

3740
voltageOutRequest = new VoltageOut(0).withEnableFOC(SwerveConstants.USE_PHOENIX_PRO_FOC);
3841
}

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

+6-6
Original file line numberDiff line numberDiff line change
@@ -31,15 +31,15 @@ public SteerMotorIOSim() {
3131
positionRotations = 0.0;
3232
velocityRotationsPerSecond = 0.0;
3333

34-
MechanismConfig pidfConstants = SwerveConstants.STEER_PIDF_CONSTANTS;
34+
MechanismConfig config = SwerveConstants.STEER_PIDF_CONSTANTS;
3535

3636
// Simulation is an ideal environment that does not have friction
37-
pidfConstants =
38-
pidfConstants
39-
.withFeedforward(pidfConstants.feedforward.withStaticFeedforward(0.0))
40-
.withFeedback(pidfConstants.feedback.withPositionTolerance(0.0));
37+
config =
38+
config
39+
.withFeedforwardConfig(config.feedforwardControllerConfig().withStaticFeedforward(0.0))
40+
.withFeedbackConfig(config.feedbackControllerConfig().withPositionTolerance(0.0));
4141

42-
pidf = new SteerMotorPIDF(pidfConstants);
42+
pidf = new SteerMotorPIDF(config);
4343
}
4444

4545
@Override

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

+3-3
Original file line numberDiff line numberDiff line change
@@ -15,10 +15,10 @@ public class SteerMotorPIDF {
1515
private final PIDController feedback;
1616

1717
/** Creates a PIDF utility class. */
18-
public SteerMotorPIDF(MechanismConfig pidfConstants) {
19-
feedforward = pidfConstants.feedforward.createSimpleMotorFeedforward();
18+
public SteerMotorPIDF(MechanismConfig config) {
19+
feedforward = config.feedforwardControllerConfig().createSimpleMotorFeedforward();
2020

21-
feedback = pidfConstants.feedback.createPIDController();
21+
feedback = config.feedbackControllerConfig().createPIDController();
2222
feedback.enableContinuousInput(-0.5, 0.5);
2323
}
2424

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

+3-3
Original file line numberDiff line numberDiff line change
@@ -154,7 +154,7 @@ private static double calculateKv(double voltsPerRotorRotationPerSecond) {
154154

155155
public static final MechanismConfig DRIVE_PIDF_CONSTANTS =
156156
new MechanismConfig()
157-
.withFeedforward(
157+
.withFeedforwardConfig(
158158
new FeedforwardControllerConfig()
159159
.withStaticFeedforward(0.14) // volts
160160
.withVelocityFeedforward(calculateKv(0.12)) // volts per meter per second
@@ -163,10 +163,10 @@ private static double calculateKv(double voltsPerRotorRotationPerSecond) {
163163
/** Constants for steer motor PIDF position controllers. */
164164
public static final MechanismConfig STEER_PIDF_CONSTANTS =
165165
new MechanismConfig()
166-
.withFeedforward(
166+
.withFeedforwardConfig(
167167
new FeedforwardControllerConfig().withStaticFeedforward(0.205) // volts
168168
)
169-
.withFeedback(
169+
.withFeedbackConfig(
170170
new FeedbackControllerConfig()
171171
.withProportionalGain(54.0) // volts per rotation
172172
.withDerivativeGain(0.16) // volts per rotation per second

0 commit comments

Comments
 (0)