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

Commit 78c543c

Browse files
committed
refactor: Use functions for modifying builders.
1 parent d722003 commit 78c543c

File tree

6 files changed

+65
-96
lines changed

6 files changed

+65
-96
lines changed

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

+12-10
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,7 @@
66
import frc.lib.config.MotionProfileConfig.MotionProfileConfigBuilder;
77
import frc.lib.config.MotorConfig.MotorConfigBuilder;
88
import java.util.Objects;
9+
import java.util.function.Function;
910

1011
/** Mechanism config. */
1112
public record MechanismConfig(
@@ -68,31 +69,32 @@ private MechanismConfigBuilder(
6869
}
6970

7071
public MechanismConfigBuilder absoluteEncoderConfig(
71-
AbsoluteEncoderConfigBuilder absoluteEncoderConfigBuilder) {
72-
this.absoluteEncoderConfigBuilder = absoluteEncoderConfigBuilder;
72+
Function<AbsoluteEncoderConfigBuilder, AbsoluteEncoderConfigBuilder> modifier) {
73+
this.absoluteEncoderConfigBuilder = modifier.apply(absoluteEncoderConfigBuilder);
7374
return this;
7475
}
7576

7677
public MechanismConfigBuilder feedbackControllerConfig(
77-
FeedbackControllerConfigBuilder feedbackControllerConfigBuilder) {
78-
this.feedbackControllerConfigBuilder = feedbackControllerConfigBuilder;
78+
Function<FeedbackControllerConfigBuilder, FeedbackControllerConfigBuilder> modifier) {
79+
this.feedbackControllerConfigBuilder = modifier.apply(feedbackControllerConfigBuilder);
7980
return this;
8081
}
8182

8283
public MechanismConfigBuilder feedforwardControllerConfig(
83-
FeedforwardControllerConfigBuilder feedforwardControllerConfigBuilder) {
84-
this.feedforwardControllerConfigBuilder = feedforwardControllerConfigBuilder;
84+
Function<FeedforwardControllerConfigBuilder, FeedforwardControllerConfigBuilder> modifier) {
85+
this.feedforwardControllerConfigBuilder = modifier.apply(feedforwardControllerConfigBuilder);
8586
return this;
8687
}
8788

8889
public MechanismConfigBuilder motionProfileConfig(
89-
MotionProfileConfigBuilder motionProfileConfigBuilder) {
90-
this.motionProfileConfigBuilder = motionProfileConfigBuilder;
90+
Function<MotionProfileConfigBuilder, MotionProfileConfigBuilder> modifier) {
91+
this.motionProfileConfigBuilder = modifier.apply(motionProfileConfigBuilder);
9192
return this;
9293
}
9394

94-
public MechanismConfigBuilder motorConfig(MotorConfigBuilder motorConfigBuilder) {
95-
this.motorConfigBuilder = motorConfigBuilder;
95+
public MechanismConfigBuilder motorConfig(
96+
Function<MotorConfigBuilder, MotorConfigBuilder> modifier) {
97+
this.motorConfigBuilder = modifier.apply(motorConfigBuilder);
9698
return this;
9799
}
98100

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

+10-18
Original file line numberDiff line numberDiff line change
@@ -7,13 +7,8 @@
77
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
88
import frc.lib.Subsystem;
99
import frc.lib.Telemetry;
10-
import frc.lib.config.AbsoluteEncoderConfig.AbsoluteEncoderConfigBuilder;
11-
import frc.lib.config.FeedbackControllerConfig.FeedbackControllerConfigBuilder;
12-
import frc.lib.config.FeedforwardControllerConfig.FeedforwardControllerConfigBuilder;
1310
import frc.lib.config.MechanismConfig;
1411
import frc.lib.config.MechanismConfig.MechanismConfigBuilder;
15-
import frc.lib.config.MotionProfileConfig.MotionProfileConfigBuilder;
16-
import frc.lib.config.MotorConfig.MotorConfigBuilder;
1712
import frc.lib.controller.PositionControllerIO;
1813
import frc.lib.controller.PositionControllerIO.PositionControllerIOValues;
1914

@@ -27,21 +22,18 @@ public class Arm extends Subsystem {
2722
private final MechanismConfig shoulderConfig =
2823
MechanismConfigBuilder.defaults()
2924
.absoluteEncoderConfig(
30-
AbsoluteEncoderConfigBuilder.defaults()
31-
.ccwPositive(false)
32-
.offset(Rotation2d.fromDegrees(-173.135)))
25+
absoluteEncoder ->
26+
absoluteEncoder.ccwPositive(false).offset(Rotation2d.fromDegrees(-173.135)))
3327
.motorConfig(
34-
MotorConfigBuilder.defaults()
35-
.ccwPositive(true)
36-
.neutralBrake(true)
37-
.motorToMechanismRatio(39.771428571))
28+
motor ->
29+
motor.ccwPositive(true).neutralBrake(true).motorToMechanismRatio(39.771428571))
3830
.motionProfileConfig(
39-
MotionProfileConfigBuilder.defaults()
40-
.maximumVelocity(Units.degreesToRotations(240.0))
41-
.maximumAcceleration(Units.degreesToRotations(240.0)))
42-
.feedforwardControllerConfig(
43-
FeedforwardControllerConfigBuilder.defaults().kS(0.14).kG(0.5125).kV(4.0))
44-
.feedbackControllerConfig(FeedbackControllerConfigBuilder.defaults().kP(4.0))
31+
motionProfile ->
32+
motionProfile
33+
.maximumVelocity(Units.degreesToRotations(240.0))
34+
.maximumAcceleration(Units.degreesToRotations(240.0)))
35+
.feedforwardControllerConfig(feedforward -> feedforward.kS(0.14).kG(0.5125).kV(4.0))
36+
.feedbackControllerConfig(feedback -> feedback.kP(4.0))
4537
.build();
4638

4739
/** Shoulder controller. */

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

+10-20
Original file line numberDiff line numberDiff line change
@@ -3,12 +3,8 @@
33
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
44
import edu.wpi.first.wpilibj2.command.button.Trigger;
55
import frc.lib.Subsystem;
6-
import frc.lib.config.FeedbackControllerConfig.FeedbackControllerConfigBuilder;
7-
import frc.lib.config.FeedforwardControllerConfig.FeedforwardControllerConfigBuilder;
86
import frc.lib.config.MechanismConfig;
97
import frc.lib.config.MechanismConfig.MechanismConfigBuilder;
10-
import frc.lib.config.MotionProfileConfig.MotionProfileConfigBuilder;
11-
import frc.lib.config.MotorConfig.MotorConfigBuilder;
128
import frc.lib.controller.VelocityControllerIO;
139
import frc.lib.controller.VelocityControllerIO.VelocityControllerIOValues;
1410

@@ -22,28 +18,22 @@ public class Intake extends Subsystem {
2218
private final MechanismConfig frontRollerConfig =
2319
MechanismConfigBuilder.defaults()
2420
.motorConfig(
25-
MotorConfigBuilder.defaults()
26-
.ccwPositive(false)
27-
.neutralBrake(false)
28-
.motorToMechanismRatio(24.0 / 16.0))
29-
.motionProfileConfig(MotionProfileConfigBuilder.defaults().maximumVelocity(66))
30-
.feedforwardControllerConfig(
31-
FeedforwardControllerConfigBuilder.defaults().kS(0.13).kV(0.1683))
32-
.feedbackControllerConfig(FeedbackControllerConfigBuilder.defaults().kP(0.1))
21+
motor ->
22+
motor.ccwPositive(false).neutralBrake(false).motorToMechanismRatio(24.0 / 16.0))
23+
.motionProfileConfig(motionProfile -> motionProfile.maximumVelocity(66))
24+
.feedforwardControllerConfig(feedforward -> feedforward.kS(0.13).kV(0.1683))
25+
.feedbackControllerConfig(feedback -> feedback.kP(0.1))
3326
.build();
3427

3528
/** Back roller controller config. */
3629
private final MechanismConfig backRollerConfig =
3730
MechanismConfigBuilder.defaults()
3831
.motorConfig(
39-
MotorConfigBuilder.defaults()
40-
.ccwPositive(false)
41-
.neutralBrake(false)
42-
.motorToMechanismRatio(24.0 / 16.0))
43-
.motionProfileConfig(MotionProfileConfigBuilder.defaults().maximumVelocity(66))
44-
.feedforwardControllerConfig(
45-
FeedforwardControllerConfigBuilder.defaults().kS(0.13).kV(0.1759))
46-
.feedbackControllerConfig(FeedbackControllerConfigBuilder.defaults().kP(0.1))
32+
motor ->
33+
motor.ccwPositive(false).neutralBrake(false).motorToMechanismRatio(24.0 / 16.0))
34+
.motionProfileConfig(motionProfile -> motionProfile.maximumVelocity(66))
35+
.feedforwardControllerConfig(feedforward -> feedforward.kS(0.13).kV(0.1759))
36+
.feedbackControllerConfig(feedback -> feedback.kP(0.1))
4737
.build();
4838

4939
/** Rollers. */

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

+13-19
Original file line numberDiff line numberDiff line change
@@ -4,12 +4,8 @@
44
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
55
import edu.wpi.first.wpilibj2.command.button.Trigger;
66
import frc.lib.Subsystem;
7-
import frc.lib.config.FeedbackControllerConfig.FeedbackControllerConfigBuilder;
8-
import frc.lib.config.FeedforwardControllerConfig.FeedforwardControllerConfigBuilder;
97
import frc.lib.config.MechanismConfig;
108
import frc.lib.config.MechanismConfig.MechanismConfigBuilder;
11-
import frc.lib.config.MotionProfileConfig.MotionProfileConfigBuilder;
12-
import frc.lib.config.MotorConfig.MotorConfigBuilder;
139
import frc.lib.controller.VelocityControllerIO;
1410
import frc.lib.controller.VelocityControllerIO.VelocityControllerIOValues;
1511

@@ -23,15 +19,12 @@ public class Shooter extends Subsystem {
2319
private final MechanismConfig flywheelConfig =
2420
MechanismConfigBuilder.defaults()
2521
.motorConfig(
26-
MotorConfigBuilder.defaults()
27-
.ccwPositive(false)
28-
.neutralBrake(true)
29-
.motorToMechanismRatio(28.0 / 16.0))
22+
motor ->
23+
motor.ccwPositive(false).neutralBrake(true).motorToMechanismRatio(28.0 / 16.0))
3024
.motionProfileConfig(
31-
MotionProfileConfigBuilder.defaults().maximumVelocity(60).maximumAcceleration(200))
32-
.feedforwardControllerConfig(
33-
FeedforwardControllerConfigBuilder.defaults().kS(0.14).kV(0.2))
34-
.feedbackControllerConfig(FeedbackControllerConfigBuilder.defaults().kP(0.14))
25+
motionProfile -> motionProfile.maximumVelocity(60).maximumAcceleration(200))
26+
.feedforwardControllerConfig(feedforward -> feedforward.kS(0.14).kV(0.2))
27+
.feedbackControllerConfig(feedback -> feedback.kP(0.14))
3528
.build();
3629

3730
/** Flywheel controller. */
@@ -47,14 +40,15 @@ public class Shooter extends Subsystem {
4740
private final MechanismConfig serializerConfig =
4841
MechanismConfigBuilder.defaults()
4942
.motorConfig(
50-
MotorConfigBuilder.defaults()
51-
.ccwPositive(true)
52-
.neutralBrake(false)
53-
.motorToMechanismRatio(36.0 / 16.0))
43+
motorConfig ->
44+
motorConfig
45+
.ccwPositive(true)
46+
.neutralBrake(false)
47+
.motorToMechanismRatio(36.0 / 16.0))
5448
.motionProfileConfig(
55-
MotionProfileConfigBuilder.defaults().maximumVelocity(45).maximumAcceleration(450))
56-
.feedforwardControllerConfig(
57-
FeedforwardControllerConfigBuilder.defaults().kS(0.14).kV(0.2617))
49+
motionProfileConfig ->
50+
motionProfileConfig.maximumVelocity(45).maximumAcceleration(450))
51+
.feedforwardControllerConfig(feedforwardConfig -> feedforwardConfig.kS(0.14).kV(0.2617))
5852
.build();
5953

6054
/** Serializer controller. */

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

+12-20
Original file line numberDiff line numberDiff line change
@@ -14,13 +14,10 @@
1414
import frc.lib.DriveRequest;
1515
import frc.lib.Subsystem;
1616
import frc.lib.Telemetry;
17-
import frc.lib.config.FeedbackControllerConfig.FeedbackControllerConfigBuilder;
18-
import frc.lib.config.FeedforwardControllerConfig.FeedforwardControllerConfigBuilder;
1917
import frc.lib.config.MechanismConfig;
2018
import frc.lib.config.MechanismConfig.MechanismConfigBuilder;
2119
import frc.lib.config.MotionProfileConfig;
2220
import frc.lib.config.MotionProfileConfig.MotionProfileConfigBuilder;
23-
import frc.lib.config.MotorConfig.MotorConfigBuilder;
2421
import frc.lib.controller.SwerveModuleIO;
2522
import frc.robot.RobotConstants;
2623
import frc.robot.odometry.Odometry;
@@ -42,30 +39,25 @@ public class Swerve extends Subsystem {
4239
private final MechanismConfig steerConfig =
4340
MechanismConfigBuilder.defaults()
4441
.motorConfig(
45-
MotorConfigBuilder.defaults()
46-
.ccwPositive(false)
47-
.currentLimitAmps(20)
48-
.motorToMechanismRatio(150.0 / 7.0))
49-
.feedforwardControllerConfig(FeedforwardControllerConfigBuilder.defaults().kS(0.205))
42+
motor ->
43+
motor.ccwPositive(false).currentLimitAmps(20).motorToMechanismRatio(150.0 / 7.0))
44+
.feedforwardControllerConfig(feedforward -> feedforward.kS(0.205))
5045
.feedbackControllerConfig(
51-
FeedbackControllerConfigBuilder.defaults()
52-
.continuous(true)
53-
.kP(54.0)
54-
.kD(0.16)
55-
.positionTolerance(Units.degreesToRotations(1.0)))
46+
feedback ->
47+
feedback
48+
.continuous(true)
49+
.kP(54.0)
50+
.kD(0.16)
51+
.positionTolerance(Units.degreesToRotations(1.0)))
5652
.build();
5753

5854
/** Drive motor config. */
5955
private final MechanismConfig driveConfig =
6056
MechanismConfigBuilder.defaults()
6157
.motorConfig(
62-
MotorConfigBuilder.defaults()
63-
.ccwPositive(false)
64-
.currentLimitAmps(40.0)
65-
.motorToMechanismRatio(6.75))
66-
.feedforwardControllerConfig(
67-
FeedforwardControllerConfigBuilder.defaults().kS(0.14).kV(0.725))
68-
.feedbackControllerConfig(FeedbackControllerConfigBuilder.defaults().kP(0.75))
58+
motor -> motor.ccwPositive(false).currentLimitAmps(40.0).motorToMechanismRatio(6.75))
59+
.feedforwardControllerConfig(feedforward -> feedforward.kS(0.14).kV(0.725))
60+
.feedbackControllerConfig(feedback -> feedback.kP(0.75))
6961
.build();
7062

7163
/** Wheel circumference. */

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

+8-9
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,6 @@
44
import edu.wpi.first.math.geometry.Translation2d;
55
import edu.wpi.first.math.util.Units;
66
import frc.lib.CAN;
7-
import frc.lib.config.AbsoluteEncoderConfig.AbsoluteEncoderConfigBuilder;
87
import frc.lib.config.MechanismConfig;
98
import frc.lib.config.MechanismConfig.MechanismConfigBuilder;
109
import frc.lib.controller.PositionControllerIO;
@@ -53,8 +52,8 @@ public static SwerveModuleIO createNorthWestModule(
5352
new CAN(24, "swerve"),
5453
MechanismConfigBuilder.from(steerConfig)
5554
.absoluteEncoderConfig(
56-
AbsoluteEncoderConfigBuilder.defaults()
57-
.offset(Rotation2d.fromRotations(-0.084716).unaryMinus()))
55+
absoluteEncoderConfig ->
56+
absoluteEncoderConfig.offset(Rotation2d.fromRotations(-0.084716).unaryMinus()))
5857
.build(),
5958
driveConfig,
6059
wheelCircumference);
@@ -82,8 +81,8 @@ public static SwerveModuleIO createNorthEastModule(
8281
new CAN(30, "swerve"),
8382
MechanismConfigBuilder.from(steerConfig)
8483
.absoluteEncoderConfig(
85-
AbsoluteEncoderConfigBuilder.defaults()
86-
.offset(Rotation2d.fromRotations(0.196777).unaryMinus()))
84+
absoluteEncoderConfig ->
85+
absoluteEncoderConfig.offset(Rotation2d.fromRotations(0.196777).unaryMinus()))
8786
.build(),
8887
driveConfig,
8988
wheelCircumference);
@@ -111,8 +110,8 @@ public static SwerveModuleIO createSouthEastModule(
111110
new CAN(26, "swerve"),
112111
MechanismConfigBuilder.from(steerConfig)
113112
.absoluteEncoderConfig(
114-
AbsoluteEncoderConfigBuilder.defaults()
115-
.offset(Rotation2d.fromRotations(0.276611).unaryMinus()))
113+
absoluteEncoderConfig ->
114+
absoluteEncoderConfig.offset(Rotation2d.fromRotations(0.276611).unaryMinus()))
116115
.build(),
117116
driveConfig,
118117
wheelCircumference);
@@ -140,8 +139,8 @@ public static SwerveModuleIO createSouthWestModule(
140139
new CAN(28, "swerve"),
141140
MechanismConfigBuilder.from(steerConfig)
142141
.absoluteEncoderConfig(
143-
AbsoluteEncoderConfigBuilder.defaults()
144-
.offset(Rotation2d.fromRotations(0.223145).unaryMinus()))
142+
absoluteEncoderConfig ->
143+
absoluteEncoderConfig.offset(Rotation2d.fromRotations(0.223145).unaryMinus()))
145144
.build(),
146145
driveConfig,
147146
wheelCircumference);

0 commit comments

Comments
 (0)